From 1e985f3aed7ec8f2b61b8fbd7d2c56d3028341cc Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Thu, 28 Jun 2012 16:01:27 -0700 Subject: [PATCH 001/543] MixerCurve: start branch with integrated mixer curve widget featuring all heli coolness for every curve. --- .../uavobjectwidgetutils/mixercurve.cpp | 14 +++ .../plugins/uavobjectwidgetutils/mixercurve.h | 22 +++++ .../uavobjectwidgetutils/mixercurve.ui | 85 +++++++++++++++++++ .../uavobjectwidgetutils.pro | 9 +- 4 files changed, 128 insertions(+), 2 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp create mode 100644 ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h create mode 100644 ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp new file mode 100644 index 000000000..4997f1493 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp @@ -0,0 +1,14 @@ +#include "mixercurve.h" +#include "ui_mixercurve.h" + +MixerCurve::MixerCurve(QWidget *parent) : + QFrame(parent), + ui(new Ui::MixerCurve) +{ + ui->setupUi(this); +} + +MixerCurve::~MixerCurve() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h new file mode 100644 index 000000000..a4e7fdf6a --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h @@ -0,0 +1,22 @@ +#ifndef MIXERCURVE_H +#define MIXERCURVE_H + +#include + +namespace Ui { +class MixerCurve; +} + +class MixerCurve : public QFrame +{ + Q_OBJECT + +public: + explicit MixerCurve(QWidget *parent = 0); + ~MixerCurve(); + +private: + Ui::MixerCurve *ui; +}; + +#endif // MIXERCURVE_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui new file mode 100644 index 000000000..48573bf24 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui @@ -0,0 +1,85 @@ + + + MixerCurve + + + + 0 + 0 + 322 + 300 + + + + MixerCurve + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + 80 + 40 + 221 + 241 + + + + + + + 20 + 260 + 51 + 22 + + + + + + + 20 + 40 + 51 + 22 + + + + + + + 10 + 70 + 61 + 181 + + + + 5 + + + 1 + + + + + + + + + + + + MixerCurveWidget + QWidget +
mixercurvewidget.h
+ 1 +
+
+ + +
diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutils.pro b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutils.pro index caacc1e9c..e4a0fee99 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutils.pro +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutils.pro @@ -10,13 +10,18 @@ HEADERS += uavobjectwidgetutils_global.h \ mixercurvewidget.h \ mixercurvepoint.h \ mixercurveline.h \ - smartsavebutton.h + smartsavebutton.h \ + mixercurve.h SOURCES += uavobjectwidgetutilsplugin.cpp \ configtaskwidget.cpp \ mixercurvewidget.cpp \ mixercurvepoint.cpp \ mixercurveline.cpp \ - smartsavebutton.cpp + smartsavebutton.cpp \ + mixercurve.cpp OTHER_FILES += UAVObjectWidgetUtils.pluginspec + +FORMS += \ + mixercurve.ui From 7f3a810fa605c29d4830ac6281f8d2daa2c096ac Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sat, 30 Jun 2012 14:35:38 -0700 Subject: [PATCH 002/543] MixerCurve: alpha version of integrated mixer curve; only in fixedwing config currently. --- .../src/plugins/config/airframe.ui | 60 +--- .../config/configvehicletypewidget.cpp | 21 +- .../plugins/config/configvehicletypewidget.h | 1 - .../uavobjectwidgetutils/mixercurve.cpp | 259 +++++++++++++++- .../plugins/uavobjectwidgetutils/mixercurve.h | 49 ++- .../uavobjectwidgetutils/mixercurve.ui | 284 ++++++++++++++++-- .../uavobjectwidgetutils/mixercurvewidget.cpp | 14 +- .../uavobjectwidgetutils/mixercurvewidget.h | 4 +- 8 files changed, 596 insertions(+), 96 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 47006a789..8fd8ce73e 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -471,23 +471,7 @@ margin:1px; - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 20 - - - - - - + 0 @@ -496,14 +480,14 @@ margin:1px; - 100 - 100 + 350 + 350 - 200 - 200 + 500 + 500 @@ -514,26 +498,6 @@ margin:1px; - - - - - 200 - 16777215 - - - - Reset - - - - - - - Val: 0.00 - - - @@ -2784,14 +2748,14 @@ p, li { white-space: pre-wrap; } <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;"> +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> <table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;"> <tr> <td style="border: none;"> <p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD IS DANGEROUS</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</p> -<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</p></td></tr></table></body></html> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</span></p> +<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</span></p></td></tr></table></body></html> @@ -2889,7 +2853,7 @@ p, li { white-space: pre-wrap; } MixerCurveWidget QWidget -
mixercurvewidget.h
+
uavobjectwidgetutils/mixercurvewidget.h
1
@@ -2898,6 +2862,12 @@ p, li { white-space: pre-wrap; }
cfg_vehicletypes/configccpmwidget.h
1
+ + MixerCurve + QWidget +
uavobjectwidgetutils/mixercurve.h
+ 1 +
diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 84b531d6b..293821d55 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -207,7 +207,7 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi //mdl connect(m_heli->m_ccpm->ccpmType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString))); //Connect throttle curve reset pushbuttons to reset functions - connect(m_aircraft->fwThrottleReset, SIGNAL(clicked()), this, SLOT(resetFwMixer())); + //connect(m_aircraft->fwThrottleReset, SIGNAL(clicked()), this, SLOT(resetFwMixer())); connect(m_aircraft->mrThrottleCurveReset, SIGNAL(clicked()), this, SLOT(resetMrMixer())); connect(m_aircraft->gvThrottleCurve1Reset, SIGNAL(clicked()), this, SLOT(resetGvFrontMixer())); connect(m_aircraft->gvThrottleCurve2Reset, SIGNAL(clicked()), this, SLOT(resetGvRearMixer())); @@ -487,7 +487,7 @@ void ConfigVehicleTypeWidget::resetFwMixer() { UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); UAVObjectField* field = obj->getField(QString("ThrottleCurve1")); - resetMixer(m_aircraft->fixedWingThrottle, field->getNumElements(),1); + //resetMixer(m_aircraft->fixedWingThrottle, field->getNumElements(),1); } /** @@ -497,7 +497,7 @@ void ConfigVehicleTypeWidget::resetMrMixer() { UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); UAVObjectField* field = obj->getField(QString("ThrottleCurve1")); - resetMixer(m_aircraft->multiThrottleCurve, field->getNumElements(),0.9); + //resetMixer(m_aircraft->multiThrottleCurve, field->getNumElements(),0.9); } /** @@ -507,7 +507,7 @@ void ConfigVehicleTypeWidget::resetGvFrontMixer() { UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); UAVObjectField* field = obj->getField(QString("ThrottleCurve1")); - resetMixer(m_aircraft->groundVehicleThrottle1, field->getNumElements(),1); + //resetMixer(m_aircraft->groundVehicleThrottle1, field->getNumElements(),1); } /** @@ -517,7 +517,7 @@ void ConfigVehicleTypeWidget::resetGvRearMixer() { UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); UAVObjectField* field = obj->getField(QString("ThrottleCurve2")); - resetMixer(m_aircraft->groundVehicleThrottle2, field->getNumElements(),1); + //resetMixer(m_aircraft->groundVehicleThrottle2, field->getNumElements(),1); } /** @@ -537,7 +537,7 @@ void ConfigVehicleTypeWidget::resetCt2Mixer() { UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); UAVObjectField* field = obj->getField(QString("ThrottleCurve2")); - resetMixer(m_aircraft->customThrottle2Curve, field->getNumElements(),1); + //resetMixer(m_aircraft->customThrottle2Curve, field->getNumElements(),1); } @@ -550,15 +550,6 @@ void ConfigVehicleTypeWidget::resetMixer(MixerCurveWidget *mixer, int numElement mixer->initLinearCurve((quint32)numElements,maxvalue); } -/** - Updates the currently moved fixed wing throttle curve item value - */ -void ConfigVehicleTypeWidget::updateFwThrottleCurveValue(QList list, double value) -{ - Q_UNUSED(list); - m_aircraft->fwThrottleCurveItemValue->setText(QString().sprintf("Val: %.2f",value)); -} - /** Updates the currently moved multi-rotor throttle curve item value */ diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h index 3cca72ba1..fb7571cd2 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h @@ -99,7 +99,6 @@ private slots: void resetGvRearMixer(); void resetCt1Mixer(); void resetCt2Mixer(); - void updateFwThrottleCurveValue(QList list, double value); void updateMrThrottleCurveValue(QList list, double value); void updateGvThrottle1CurveValue(QList list, double value); void updateGvThrottle2CurveValue(QList list, double value); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp index 4997f1493..c319138dd 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp @@ -1,14 +1,265 @@ +#include #include "mixercurve.h" -#include "ui_mixercurve.h" MixerCurve::MixerCurve(QWidget *parent) : QFrame(parent), - ui(new Ui::MixerCurve) + m_mixerUI(new Ui::MixerCurve), + m_curveType(MixerCurve::MIXERCURVE_THROTTLE) { - ui->setupUi(this); + m_mixerUI->setupUi(this); + + m_curve = m_mixerUI->CurveWidget; + m_settings = m_mixerUI->CurveSettings; + + UpdateCurveSettings(); + + connect(m_mixerUI->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(UpdateCurveSettings())); + connect(m_mixerUI->ResetCurve, SIGNAL(clicked()), this, SLOT(ResetCurve())); + connect(m_mixerUI->GenerateCurve, SIGNAL(clicked()), this, SLOT(GenerateCurve())); + connect(m_curve, SIGNAL(curveUpdated()), this, SLOT(UpdateSettings())); + + connect(m_mixerUI->CurveMin, SIGNAL(valueChanged(double)), this, SLOT(CurveMinChanged(double))); + connect(m_mixerUI->CurveMax, SIGNAL(valueChanged(double)), this, SLOT(CurveMaxChanged(double))); + connect(m_mixerUI->CurveStep, SIGNAL(valueChanged(double)), this, SLOT(GenerateCurve())); } MixerCurve::~MixerCurve() { - delete ui; + delete m_mixerUI; +} + +void MixerCurve::ResetCurve() +{ + m_curve->setMin((m_curveType == MixerCurve::MIXERCURVE_THROTTLE) ? 0.0 : -1.0); + m_curve->setMax(1.0); + + m_mixerUI->CurveMin->setValue(m_curve->getMin()); + m_mixerUI->CurveMax->setValue(m_curve->getMax()); + + initLinearCurve(MixerCurveWidget::NODE_NUMELEM, m_curve->getMax(), m_curve->getMin()); + + UpdateSettings(); +} + +void MixerCurve::UpdateCurveSettings() +{ + //get the user settings + QString curveType = m_mixerUI->CurveType->currentText(); + + switch (m_curveType) { + case MixerCurve::MIXERCURVE_THROTTLE: + { + m_mixerUI->CurveMin->setMinimum(0.0); + m_mixerUI->CurveMax->setMinimum(0.0); + m_mixerUI->CurveStep->setMinimum(0.0); + break; + } + case MixerCurve::MIXERCURVEPITCH: + { + m_mixerUI->CurveMin->setMinimum(-1.0); + m_mixerUI->CurveMax->setMinimum(-1.0); + m_mixerUI->CurveStep->setMinimum(0.0); + break; + } + } + m_mixerUI->CurveMin->setMaximum(1.0); + m_mixerUI->CurveMax->setMaximum(1.0); + m_mixerUI->CurveStep->setMaximum(100.0); + + //set default visible + m_mixerUI->minLabel->setText("Min"); + m_mixerUI->minLabel->setVisible(true); + m_mixerUI->CurveMin->setVisible(true); + m_mixerUI->maxLabel->setVisible(false); + m_mixerUI->CurveMax->setVisible(false); + m_mixerUI->stepLabel->setVisible(false); + m_mixerUI->CurveStep->setVisible(false); + + if ( curveType.compare("Flat")==0) + { + m_mixerUI->minLabel->setText("Value"); + } + if ( curveType.compare("Linear")==0) + { + m_mixerUI->maxLabel->setVisible(true); + m_mixerUI->CurveMax->setVisible(true); + } + if ( curveType.compare("Step")==0) + { + m_mixerUI->maxLabel->setVisible(true); + m_mixerUI->CurveMax->setVisible(true); + m_mixerUI->stepLabel->setText("Step at"); + m_mixerUI->stepLabel->setVisible(true); + m_mixerUI->CurveStep->setVisible(true); + } + if ( curveType.compare("Exp")==0) + { + m_mixerUI->maxLabel->setVisible(true); + m_mixerUI->CurveMax->setVisible(true); + m_mixerUI->stepLabel->setText("Strength"); + m_mixerUI->stepLabel->setVisible(true); + m_mixerUI->CurveStep->setVisible(true); + } + if ( curveType.compare("Log")==0) + { + m_mixerUI->maxLabel->setVisible(true); + m_mixerUI->CurveMax->setVisible(true); + m_mixerUI->stepLabel->setText("Strength"); + m_mixerUI->stepLabel->setVisible(true); + m_mixerUI->CurveStep->setVisible(true); + } +} + +void MixerCurve::GenerateCurve() +{ + double scale; + double newValue; + + //get the user settings + double value1 = getMin(); + double value2 = getMax(); + double value3 = getStep(); + + QString CurveType = m_mixerUI->CurveType->currentText(); + + QList points; + + for (int i=0; i* points) +{ + m_curve->initCurve(points); + UpdateSettings(); +} + +QList MixerCurve::getCurve() +{ + return m_curve->getCurve(); +} + +void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue) +{ + m_curve->initLinearCurve(numPoints, maxValue, minValue); +} + +void MixerCurve::setCurve(const QList* points) +{ + m_curve->setCurve(points); + UpdateSettings(); +} + +void MixerCurve::setMin(double value) +{ + m_curve->setMin(value); +} + +double MixerCurve::getMin() +{ + return m_curve->getMin(); +} + +void MixerCurve::setMax(double value) +{ + m_curve->setMax(value); +} + +double MixerCurve::getMax() +{ + return m_curve->getMax(); +} + +double MixerCurve::getStep() +{ + return m_mixerUI->CurveStep->value(); +} + +void MixerCurve::UpdateSettings() +{ + QList points = m_curve->getCurve(); + + int ptCnt = points.count(); + for (int i=0; iitem((ptCnt - 1) - i, 0); + if (item) + item->setText(QString().sprintf("%.2f",points.at(i))); + } +} + +void MixerCurve::CurveMinChanged(double value) +{ + setMin(value); + + // the min changed so redraw the curve + // mixercurvewidget::setCurve will trim any points below min + QList points = getCurve(); + setCurve(&points); +} + +void MixerCurve::CurveMaxChanged(double value) +{ + setMax(value); + + // the max changed so redraw the curve + // mixercurvewidget::setCurve will trim any points above max + QList points = getCurve(); + setCurve(&points); +} + +double MixerCurve::setRange(double min, double max) +{ + return m_curve->setRange(min, max); +} + +void MixerCurve::showEvent(QShowEvent *event) +{ + Q_UNUSED(event) + // Thit fitInView method should only be called now, once the + // widget is shown, otherwise it cannot compute its values and + // the result is usually a ahrsbargraph that is way too small. + //fitInView(this, Qt::KeepAspectRatio); + +} + +void MixerCurve::resizeEvent(QResizeEvent* event) +{ + Q_UNUSED(event); + //fitInView(this, Qt::KeepAspectRatio); } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h index a4e7fdf6a..eeebe0d22 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h @@ -2,21 +2,64 @@ #define MIXERCURVE_H #include +#include +#include +#include + +#include "ui_mixercurve.h" +#include "mixercurvewidget.h" +#include "uavobjectwidgetutils_global.h" namespace Ui { class MixerCurve; } -class MixerCurve : public QFrame +class UAVOBJECTWIDGETUTILS_EXPORT MixerCurve : public QFrame { Q_OBJECT public: explicit MixerCurve(QWidget *parent = 0); ~MixerCurve(); - + + + /* Enumeration options for ThrottleCurves */ + typedef enum { MIXERCURVE_THROTTLE=0, MIXERCURVEPITCH=1 } MixerCurveType; + + void initCurve (const QList* points); + QList getCurve(); + void initLinearCurve(int numPoints, double maxValue = 1, double minValue = 0); + void setCurve(const QList* points); + void setMin(double value); + double getMin(); + void setMax(double value); + double getMax(); + double getStep(); + double setRange(double min, double max); + + +signals: + +protected: + void showEvent(QShowEvent *event); + void resizeEvent(QResizeEvent *event); + +public slots: + void ResetCurve(); + void GenerateCurve(); + void UpdateSettings(); + +private slots: + void CurveMinChanged(double value); + void CurveMaxChanged(double value); + void UpdateCurveSettings(); + private: - Ui::MixerCurve *ui; + Ui::MixerCurve* m_mixerUI; + MixerCurveWidget* m_curve; + QTableWidget* m_settings; + MixerCurveType m_curveType; + }; #endif // MIXERCURVE_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui index 48573bf24..67ad97fe2 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui @@ -6,10 +6,28 @@ 0 0 - 322 - 300 + 437 + 317 + + + 365 + 306 + + + + + 500 + 500 + + + + + 300 + 300 + + MixerCurve @@ -19,64 +37,282 @@ QFrame::Raised - + - 80 - 40 - 221 + 140 + 10 + 291 + 300 + + + + + 261 241 - + + + + + 300 + 300 + - + - 20 - 260 + 70 + 240 51 22 + + QAbstractSpinBox::CorrectToNearestValue + + + -1.000000000000000 + + + 1.000000000000000 + + + 0.010000000000000 + + + 0.000000000000000 + - + - 20 + 70 40 51 22 + + QAbstractSpinBox::CorrectToNearestValue + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.010000000000000 + + + 1.000000000000000 + - + - 10 - 70 - 61 - 181 + 20 + 60 + 101 + 171 + + + 8 + + + + Qt::ScrollBarAlwaysOff + + + Qt::ScrollBarAlwaysOff + + + false + 5 1 - - - - - - + + + 5 + + + + + 4 + + + + + 3 + + + + + 2 + + + + + 1 + + + + + Value + + + + + 1.0 + + + + + .75 + + + + + .50 + + + + + .25 + + + + + .00 + + + + + + + 0 + 10 + 61 + 22 + + + + + Linear + + + + + Log + + + + + Exp + + + + + Flat + + + + + Step + + + + + + + 70 + 10 + 61 + 23 + + + + Generate + + + + + + 20 + 240 + 41 + 16 + + + + Min + + + + + + 20 + 40 + 41 + 16 + + + + Max + + + + + + 20 + 290 + 75 + 23 + + + + Reset + + + + + + 20 + 260 + 41 + 16 + + + + Step + + + + + + 70 + 260 + 51 + 22 + + + + QAbstractSpinBox::CorrectToNearestValue + MixerCurveWidget QWidget -
mixercurvewidget.h
+
uavobjectwidgetutils/mixercurvewidget.h
1
diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index a19692ff9..eea8fef7b 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -220,12 +220,13 @@ void MixerCurveWidget::setCurve(const QList* points) Node* node = nodeList.at(i); node->setPos(w*i, h - (val*h)); node->verticalMove(true); + node->update(); } curveUpdating = false; update(); - emit curveUpdated(points, (double)0); + emit curveUpdated(); } @@ -248,19 +249,26 @@ void MixerCurveWidget::resizeEvent(QResizeEvent* event) void MixerCurveWidget::itemMoved(double itemValue) { if (!curveUpdating) { - QList curve = getCurve(); - emit curveUpdated(&curve, itemValue); + emit curveUpdated(); } } void MixerCurveWidget::setMin(double value) { + if (curveMin != value) + emit curveMinChanged(value); + curveMin = value; } + void MixerCurveWidget::setMax(double value) { + if (curveMax != value) + emit curveMaxChanged(value); + curveMax = value; } + double MixerCurveWidget::getMin() { return curveMin; diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h index 031a70733..e1275a3a5 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h @@ -57,7 +57,9 @@ public: static const int NODE_NUMELEM = 5; signals: - void curveUpdated(const QList* points, const double value); + void curveUpdated(); + void curveMinChanged(double value); + void curveMaxChanged(double value); private slots: From 09a2a007a899c4d024dd640aad8f4d0c9790a3c6 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sat, 30 Jun 2012 15:27:42 -0700 Subject: [PATCH 003/543] MixerCurve, Bugfix: use widget values for min/max for curve generation. --- .../uavobjectwidgetutils/mixercurve.cpp | 30 ++++++++++++++----- .../plugins/uavobjectwidgetutils/mixercurve.h | 4 ++- 2 files changed, 26 insertions(+), 8 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp index c319138dd..63b65d29c 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp @@ -35,6 +35,7 @@ void MixerCurve::ResetCurve() m_mixerUI->CurveMin->setValue(m_curve->getMin()); m_mixerUI->CurveMax->setValue(m_curve->getMax()); + m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Linear")); initLinearCurve(MixerCurveWidget::NODE_NUMELEM, m_curve->getMax(), m_curve->getMin()); @@ -108,6 +109,8 @@ void MixerCurve::UpdateCurveSettings() m_mixerUI->stepLabel->setVisible(true); m_mixerUI->CurveStep->setVisible(true); } + + GenerateCurve(); } void MixerCurve::GenerateCurve() @@ -116,9 +119,9 @@ void MixerCurve::GenerateCurve() double newValue; //get the user settings - double value1 = getMin(); - double value2 = getMax(); - double value3 = getStep(); + double value1 = getCurveMin(); + double value2 = getCurveMax(); + double value3 = getCurveStep(); QString CurveType = m_mixerUI->CurveType->currentText(); @@ -165,7 +168,7 @@ void MixerCurve::GenerateCurve() void MixerCurve::initCurve (const QList* points) { - m_curve->initCurve(points); + m_curve->setCurve(points); UpdateSettings(); } @@ -205,7 +208,16 @@ double MixerCurve::getMax() return m_curve->getMax(); } -double MixerCurve::getStep() +double MixerCurve::getCurveMin() +{ + return m_mixerUI->CurveMin->value(); +} +double MixerCurve::getCurveMax() +{ + return m_mixerUI->CurveMax->value(); +} + +double MixerCurve::getCurveStep() { return m_mixerUI->CurveStep->value(); } @@ -225,21 +237,25 @@ void MixerCurve::UpdateSettings() void MixerCurve::CurveMinChanged(double value) { - setMin(value); + //setMin(value); // the min changed so redraw the curve // mixercurvewidget::setCurve will trim any points below min QList points = getCurve(); + points.removeFirst(); + points.push_front(value); setCurve(&points); } void MixerCurve::CurveMaxChanged(double value) { - setMax(value); + //setMax(value); // the max changed so redraw the curve // mixercurvewidget::setCurve will trim any points above max QList points = getCurve(); + points.removeLast(); + points.append(value); setCurve(&points); } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h index eeebe0d22..fe4719544 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h @@ -34,7 +34,9 @@ public: double getMin(); void setMax(double value); double getMax(); - double getStep(); + double getCurveMin(); + double getCurveMax(); + double getCurveStep(); double setRange(double min, double max); From 8088f7aee9e4648ea2e47eff766b0db90605055d Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 2 Jul 2012 10:46:21 -0700 Subject: [PATCH 004/543] MixerCurve: wire new curve into all airframes except heli; ConfigMultiRotor: Bugfix boundary condition on channel descriptions; prune unused mixercurvewidget resets,values etc from vehicle specific configs --- .../src/plugins/config/airframe.ui | 240 +++------ .../openpilotgcs/src/plugins/config/ccpm.ui | 4 +- .../configfixedwingwidget.cpp | 6 +- .../configgroundvehiclewidget.cpp | 6 +- .../configmultirotorwidget.cpp | 21 +- .../src/plugins/config/configoutputwidget.cpp | 2 - .../config/configvehicletypewidget.cpp | 129 +---- .../plugins/config/configvehicletypewidget.h | 12 +- .../uavobjectwidgetutils/mixercurve.cpp | 15 +- .../plugins/uavobjectwidgetutils/mixercurve.h | 1 + .../uavobjectwidgetutils/mixercurve.ui | 508 +++++++++--------- .../uavobjectwidgetutils/mixercurvewidget.h | 3 + 12 files changed, 339 insertions(+), 608 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 8fd8ce73e..5a6f81895 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -6,8 +6,8 @@ 0 0 - 796 - 618 + 939 + 635 @@ -74,7 +74,7 @@ - 0 + 4 @@ -480,8 +480,8 @@ margin:1px; - 350 - 350 + 0 + 0 @@ -555,7 +555,7 @@ margin:1px; - + @@ -850,19 +850,6 @@ margin:1px; - - - - Qt::Horizontal - - - - 40 - 20 - - - - @@ -870,23 +857,7 @@ margin:1px; - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - - + 0 @@ -895,8 +866,8 @@ margin:1px; - 120 - 120 + 0 + 0 @@ -904,32 +875,6 @@ margin:1px; - - - - - 0 - 0 - - - - - 200 - 16777215 - - - - Reset - - - - - - - Val: 0.00 - - - @@ -1699,7 +1644,7 @@ margin:1px; - + 0 @@ -1708,14 +1653,14 @@ margin:1px; - 100 - 100 + 0 + 0 - 200 - 200 + 500 + 500 @@ -1726,26 +1671,6 @@ margin:1px; - - - - - 200 - 16777215 - - - - Reset - - - - - - - Val: 0.00 - - - @@ -1756,7 +1681,7 @@ margin:1px; - + 0 @@ -1765,32 +1690,18 @@ margin:1px; - 100 - 100 + 0 + 0 - 200 - 200 + 500 + 500 - - - - Reset - - - - - - - Val: 0.00 - - -
@@ -1851,25 +1762,43 @@ margin:1px; + + + 0 + 0 + + Curve 1 - + - - 0 - 0 + + 1 + 1 - 100 - 100 + 50 + 50 + + 1000 + 1000 + + + + + 10 + 10 + + + 200 200 @@ -1877,48 +1806,9 @@ margin:1px; - - - - - 0 - 0 - - - - - 0 - 0 - - - - Reset - - - - - - - Val: 0.00 - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - @@ -1926,20 +1816,32 @@ margin:1px; - + - - 0 - 0 + + 1 + 1 - 100 - 100 + 50 + 50 + + 1000 + 1000 + + + + + 10 + 10 + + + 200 200 @@ -1947,20 +1849,6 @@ margin:1px; - - - - Reset - - - - - - - Val: 0.00 - - - @@ -2850,12 +2738,6 @@ p, li { white-space: pre-wrap; }
- - MixerCurveWidget - QWidget -
uavobjectwidgetutils/mixercurvewidget.h
- 1 -
ConfigCcpmWidget QWidget diff --git a/ground/openpilotgcs/src/plugins/config/ccpm.ui b/ground/openpilotgcs/src/plugins/config/ccpm.ui index c31e5fb97..1ebb2a71b 100644 --- a/ground/openpilotgcs/src/plugins/config/ccpm.ui +++ b/ground/openpilotgcs/src/plugins/config/ccpm.ui @@ -87,7 +87,7 @@ QGroupBox::title { } - 0 + 2 @@ -3912,7 +3912,7 @@ margin:1px; MixerCurveWidget QWidget -
mixercurvewidget.h
+
uavobjectwidgetutils/mixercurvewidget.h
1
diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 7ed667828..727a2f52d 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -291,7 +291,7 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType) int channel; //disable all - for (channel=0; channel 0 && multi.VTOLMotorN < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + if (multi.VTOLMotorN > 0 && multi.VTOLMotorN <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) channelDesc[multi.VTOLMotorN-1] = QString("VTOLMotorN"); - if (multi.VTOLMotorNE > 0 && multi.VTOLMotorNE < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + if (multi.VTOLMotorNE > 0 && multi.VTOLMotorNE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) channelDesc[multi.VTOLMotorNE-1] = QString("VTOLMotorNE"); - if (multi.VTOLMotorNW > 0 && multi.VTOLMotorNW < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + if (multi.VTOLMotorNW > 0 && multi.VTOLMotorNW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) channelDesc[multi.VTOLMotorNW-1] = QString("VTOLMotorNW"); - if (multi.VTOLMotorS > 0 && multi.VTOLMotorS < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + if (multi.VTOLMotorS > 0 && multi.VTOLMotorS <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) channelDesc[multi.VTOLMotorS-1] = QString("VTOLMotorS"); - if (multi.VTOLMotorSE > 0 && multi.VTOLMotorSE < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + if (multi.VTOLMotorSE > 0 && multi.VTOLMotorSE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) channelDesc[multi.VTOLMotorSE-1] = QString("VTOLMotorSE"); - if (multi.VTOLMotorSW > 0 && multi.VTOLMotorSW < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + if (multi.VTOLMotorSW > 0 && multi.VTOLMotorSW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) channelDesc[multi.VTOLMotorSW-1] = QString("VTOLMotorSW"); - if (multi.VTOLMotorW > 0 && multi.VTOLMotorW < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + if (multi.VTOLMotorW > 0 && multi.VTOLMotorW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) channelDesc[multi.VTOLMotorW-1] = QString("VTOLMotorW"); - if (multi.VTOLMotorE > 0 && multi.VTOLMotorE < ConfigMultiRotorWidget::CHANNEL_NUMELEM) + if (multi.VTOLMotorE > 0 && multi.VTOLMotorE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) channelDesc[multi.VTOLMotorE-1] = QString("VTOLMotorE"); return channelDesc; @@ -969,7 +968,7 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3]) Q_ASSERT(mixer); //disable all - for (int channel=0; channelgroundVehicleType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString))); //mdl connect(m_heli->m_ccpm->ccpmType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString))); - //Connect throttle curve reset pushbuttons to reset functions - //connect(m_aircraft->fwThrottleReset, SIGNAL(clicked()), this, SLOT(resetFwMixer())); - connect(m_aircraft->mrThrottleCurveReset, SIGNAL(clicked()), this, SLOT(resetMrMixer())); - connect(m_aircraft->gvThrottleCurve1Reset, SIGNAL(clicked()), this, SLOT(resetGvFrontMixer())); - connect(m_aircraft->gvThrottleCurve2Reset, SIGNAL(clicked()), this, SLOT(resetGvRearMixer())); - connect(m_aircraft->customReset1, SIGNAL(clicked()), this, SLOT(resetCt1Mixer())); - connect(m_aircraft->customReset2, SIGNAL(clicked()), this, SLOT(resetCt2Mixer())); - - //Connect throttle curve manipulation points to output text - connect(m_aircraft->fixedWingThrottle, SIGNAL(curveUpdated(QList,double)), this, SLOT(updateFwThrottleCurveValue(QList,double))); - connect(m_aircraft->multiThrottleCurve, SIGNAL(curveUpdated(QList,double)), this, SLOT(updateMrThrottleCurveValue(QList,double))); - connect(m_aircraft->groundVehicleThrottle1, SIGNAL(curveUpdated(QList,double)), this, SLOT(updateGvThrottle1CurveValue(QList,double))); - connect(m_aircraft->groundVehicleThrottle2, SIGNAL(curveUpdated(QList,double)), this, SLOT(updateGvThrottle2CurveValue(QList,double))); - connect(m_aircraft->customThrottle1Curve, SIGNAL(curveUpdated(QList,double)), this, SLOT(updateCustomThrottle1CurveValue(QList,double))); - connect(m_aircraft->customThrottle2Curve, SIGNAL(curveUpdated(QList,double)), this, SLOT(updateCustomThrottle2CurveValue(QList,double))); - -// connect(m_aircraft->fwAileron1Channel, SIGNAL(currentIndexChanged(int)), this, SLOT(toggleAileron2(int))); -// connect(m_aircraft->fwElevator1Channel, SIGNAL(currentIndexChanged(int)), this, SLOT(toggleElevator2(int))); - //Connect the three feed forward test checkboxes connect(m_aircraft->ffTestBox1, SIGNAL(clicked(bool)), this, SLOT(enableFFTest())); connect(m_aircraft->ffTestBox2, SIGNAL(clicked(bool)), this, SLOT(enableFFTest())); @@ -479,68 +460,6 @@ void ConfigVehicleTypeWidget::enableFFTest() } } - -/** - Resets Fixed wing throttle mixer - */ -void ConfigVehicleTypeWidget::resetFwMixer() -{ - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - UAVObjectField* field = obj->getField(QString("ThrottleCurve1")); - //resetMixer(m_aircraft->fixedWingThrottle, field->getNumElements(),1); -} - -/** - Resets Multirotor throttle mixer - */ -void ConfigVehicleTypeWidget::resetMrMixer() -{ - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - UAVObjectField* field = obj->getField(QString("ThrottleCurve1")); - //resetMixer(m_aircraft->multiThrottleCurve, field->getNumElements(),0.9); -} - -/** - Resets Ground vehicle front throttle mixer - */ -void ConfigVehicleTypeWidget::resetGvFrontMixer() -{ - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - UAVObjectField* field = obj->getField(QString("ThrottleCurve1")); - //resetMixer(m_aircraft->groundVehicleThrottle1, field->getNumElements(),1); -} - -/** - Resets Ground vehicle rear throttle mixer - */ -void ConfigVehicleTypeWidget::resetGvRearMixer() -{ - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - UAVObjectField* field = obj->getField(QString("ThrottleCurve2")); - //resetMixer(m_aircraft->groundVehicleThrottle2, field->getNumElements(),1); -} - -/** - Resets Custom throttle 1 mixer - */ -void ConfigVehicleTypeWidget::resetCt1Mixer() -{ - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - UAVObjectField* field = obj->getField(QString("ThrottleCurve1")); - resetMixer(m_aircraft->customThrottle1Curve, field->getNumElements(),1); -} - -/** - Resets Custom throttle 2 mixer - */ -void ConfigVehicleTypeWidget::resetCt2Mixer() -{ - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - UAVObjectField* field = obj->getField(QString("ThrottleCurve2")); - //resetMixer(m_aircraft->customThrottle2Curve, field->getNumElements(),1); -} - - /** Resets a mixer curve */ @@ -550,52 +469,6 @@ void ConfigVehicleTypeWidget::resetMixer(MixerCurveWidget *mixer, int numElement mixer->initLinearCurve((quint32)numElements,maxvalue); } -/** - Updates the currently moved multi-rotor throttle curve item value - */ -void ConfigVehicleTypeWidget::updateMrThrottleCurveValue(QList list, double value) -{ - Q_UNUSED(list); - m_aircraft->mrThrottleCurveItemValue->setText(QString().sprintf("Val: %.2f",value)); -} - -/** - Updates the moved ground vehicle front throttle curve item value - */ -void ConfigVehicleTypeWidget::updateGvThrottle1CurveValue(QList list, double value) -{ - Q_UNUSED(list); - m_aircraft->gvThrottleCurve1ItemValue->setText(QString().sprintf("Val: %.2f",value)); -} - -/** - Updates the moved ground vehicle rear throttle curve item value - */ -void ConfigVehicleTypeWidget::updateGvThrottle2CurveValue(QList list, double value) -{ - Q_UNUSED(list); - m_aircraft->gvThrottleCurve2ItemValue->setText(QString().sprintf("Val: %.2f",value)); -} - -/** - Updates the currently moved custom throttle curve item value (Custom throttle 1) - */ -void ConfigVehicleTypeWidget::updateCustomThrottle1CurveValue(QList list, double value) -{ - Q_UNUSED(list); - m_aircraft->customThrottleCurve1Value->setText(QString().sprintf("Val: %.2f",value)); -} - -/** - Updates the currently moved custom throttle curve item value (Custom throttle 2) - */ -void ConfigVehicleTypeWidget::updateCustomThrottle2CurveValue(QList list, double value) -{ - Q_UNUSED(list); - m_aircraft->customThrottleCurve2Value->setText(QString().sprintf("Val: %.2f",value)); -} - - /************************** * Aircraft settings **************************/ diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h index fb7571cd2..7eb9832e6 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h @@ -93,17 +93,7 @@ private slots: void toggleElevator2(int index); void toggleRudder2(int index); void switchAirframeType(int index); - void resetFwMixer(); - void resetMrMixer(); - void resetGvFrontMixer(); - void resetGvRearMixer(); - void resetCt1Mixer(); - void resetCt2Mixer(); - void updateMrThrottleCurveValue(QList list, double value); - void updateGvThrottle1CurveValue(QList list, double value); - void updateGvThrottle2CurveValue(QList list, double value); - void updateCustomThrottle1CurveValue(QList list, double value); - void updateCustomThrottle2CurveValue(QList list, double value); + void enableFFTest(); void openHelp(); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp index 63b65d29c..5eb62485a 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp @@ -28,6 +28,11 @@ MixerCurve::~MixerCurve() delete m_mixerUI; } +void MixerCurve::setMixerType(MixerCurveType curveType) +{ + m_curveType = curveType; +} + void MixerCurve::ResetCurve() { m_curve->setMin((m_curveType == MixerCurve::MIXERCURVE_THROTTLE) ? 0.0 : -1.0); @@ -266,16 +271,14 @@ double MixerCurve::setRange(double min, double max) void MixerCurve::showEvent(QShowEvent *event) { - Q_UNUSED(event) - // Thit fitInView method should only be called now, once the - // widget is shown, otherwise it cannot compute its values and - // the result is usually a ahrsbargraph that is way too small. - //fitInView(this, Qt::KeepAspectRatio); + Q_UNUSED(event); + m_curve->showEvent(event); } void MixerCurve::resizeEvent(QResizeEvent* event) { Q_UNUSED(event); - //fitInView(this, Qt::KeepAspectRatio); + + m_curve->resizeEvent(event); } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h index fe4719544..faa326109 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h @@ -26,6 +26,7 @@ public: /* Enumeration options for ThrottleCurves */ typedef enum { MIXERCURVE_THROTTLE=0, MIXERCURVEPITCH=1 } MixerCurveType; + void setMixerType(MixerCurveType curveType); void initCurve (const QList* points); QList getCurve(); void initLinearCurve(int numPoints, double maxValue = 1, double minValue = 0); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui index 67ad97fe2..0ef6f3d80 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui @@ -6,14 +6,20 @@ 0 0 - 437 - 317 + 490 + 390 + + + 1 + 1 + + - 365 - 306 + 442 + 328 @@ -37,275 +43,251 @@ QFrame::Raised - + - 140 - 10 - 291 - 300 + 120 + 0 + 371 + 391 - - - 261 - 241 - - - - - 300 - 300 - - + + + + + + 1 + 1 + + + + + 50 + 50 + + + + + 1000 + 1000 + + + + + 10 + 10 + + + + + 200 + 200 + + + + + - - - - 70 - 240 - 51 - 22 - - - - QAbstractSpinBox::CorrectToNearestValue - - - -1.000000000000000 - - - 1.000000000000000 - - - 0.010000000000000 - - - 0.000000000000000 - - - - - - 70 - 40 - 51 - 22 - - - - QAbstractSpinBox::CorrectToNearestValue - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.010000000000000 - - - 1.000000000000000 - - - - - - 20 - 60 - 101 - 171 - - - - - 8 - - - - Qt::ScrollBarAlwaysOff - - - Qt::ScrollBarAlwaysOff - - - false - - - 5 - - - 1 - - - - 5 - - - - - 4 - - - - - 3 - - - - - 2 - - - - - 1 - - - - - Value - - - - - 1.0 - - - - - .75 - - - - - .50 - - - - - .25 - - - - - .00 - - - - + 0 - 10 - 61 - 22 + 0 + 121 + 391 - - - Linear - - - - - Log - - - - - Exp - - - - - Flat - - - - - Step - - - - - - - 70 - 10 - 61 - 23 - - - - Generate - - - - - - 20 - 240 - 41 - 16 - - - - Min - - - - - - 20 - 40 - 41 - 16 - - - - Max - - - - - - 20 - 290 - 75 - 23 - - - - Reset - - - - - - 20 - 260 - 41 - 16 - - - - Step - - - - - - 70 - 260 - 51 - 22 - - - - QAbstractSpinBox::CorrectToNearestValue - + + + + + + Linear + + + + + Log + + + + + Exp + + + + + Flat + + + + + Step + + + + + + + + Generate + + + + + + + Max + + + + + + + QAbstractSpinBox::CorrectToNearestValue + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.010000000000000 + + + 1.000000000000000 + + + + + + + + 8 + + + + Qt::ScrollBarAlwaysOff + + + Qt::ScrollBarAlwaysOff + + + false + + + 5 + + + 1 + + + + 5 + + + + + 4 + + + + + 3 + + + + + 2 + + + + + 1 + + + + + Value + + + + + 1.0 + + + + + .75 + + + + + .50 + + + + + .25 + + + + + .00 + + + + + + + + Min + + + + + + + QAbstractSpinBox::CorrectToNearestValue + + + -1.000000000000000 + + + 1.000000000000000 + + + 0.010000000000000 + + + 0.000000000000000 + + + + + + + Step + + + + + + + QAbstractSpinBox::CorrectToNearestValue + + + + + + + Reset + + + + diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h index e1275a3a5..338974f28 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h @@ -43,6 +43,9 @@ class UAVOBJECTWIDGETUTILS_EXPORT MixerCurveWidget : public QGraphicsView public: MixerCurveWidget(QWidget *parent = 0); ~MixerCurveWidget(); + + friend class MixerCurve; + void itemMoved(double itemValue); // Callback when a point is moved, to be updated void initCurve (const QList* points); QList getCurve(); From 0c9e5c5e66bd389a12c2affe667aac2835466ac7 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Wed, 4 Jul 2012 10:21:48 -0700 Subject: [PATCH 005/543] MixerCurve: Move code into \config folder; slice out doublespindelegate; enhanced mixercurve in all airframes except heli; layout is better, not there yet. VehicleConfig, Bugfix: update custom mixer table to 10 channels. --- .../src/plugins/config/DoubleSpinDelegate.cpp | 79 ++++ .../src/plugins/config/DoubleSpinDelegate.h | 57 +++ .../src/plugins/config/airframe.ui | 161 ++++++-- .../openpilotgcs/src/plugins/config/ccpm.ui | 2 +- .../src/plugins/config/config.pro | 11 +- .../config/configvehicletypewidget.cpp | 12 +- .../mixercurve.cpp | 125 ++++-- .../src/plugins/config/mixercurve.h | 97 +++++ .../src/plugins/config/mixercurve.ui | 378 ++++++++++++++++++ .../plugins/uavobjectwidgetutils/mixercurve.h | 68 ---- .../uavobjectwidgetutils/mixercurve.ui | 303 -------------- .../uavobjectwidgetutils.pro | 9 +- 12 files changed, 850 insertions(+), 452 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.cpp create mode 100644 ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.h rename ground/openpilotgcs/src/plugins/{uavobjectwidgetutils => config}/mixercurve.cpp (70%) create mode 100644 ground/openpilotgcs/src/plugins/config/mixercurve.h create mode 100644 ground/openpilotgcs/src/plugins/config/mixercurve.ui delete mode 100644 ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h delete mode 100644 ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui diff --git a/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.cpp b/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.cpp new file mode 100644 index 000000000..dd5921431 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.cpp @@ -0,0 +1,79 @@ +/** + ****************************************************************************** + * + * @file doublespindelegate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief A double spinbox delegate + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "doublespindelegate.h" + +/** + Helper delegate for the custom mixer editor table. + */ +DoubleSpinDelegate::DoubleSpinDelegate(QObject *parent) + : QItemDelegate(parent), + m_min(0.0), + m_max(1.0), + m_decimals(2), + m_step(0.01) + { + } + + +QWidget *DoubleSpinDelegate::createEditor(QWidget *parent, + const QStyleOptionViewItem &/* option */, + const QModelIndex &/* index */) const +{ + QDoubleSpinBox *editor = new QDoubleSpinBox(parent); + editor->setMinimum(m_min); + editor->setMaximum(m_max); + editor->setDecimals(m_decimals); + editor->setSingleStep(m_step); + return editor; +} + +void DoubleSpinDelegate::setEditorData(QWidget *editor, + const QModelIndex &index) const +{ + double value = index.model()->data(index, Qt::EditRole).toDouble(); + + QDoubleSpinBox *spinBox = static_cast(editor); + spinBox->setValue(value); +} + +void DoubleSpinDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, + const QModelIndex &index) const +{ + QDoubleSpinBox *spinBox = static_cast(editor); + spinBox->interpretText(); + double value = spinBox->value(); + + model->setData(index, value, Qt::EditRole); +} + +void DoubleSpinDelegate::updateEditorGeometry(QWidget *editor, + const QStyleOptionViewItem &option, const QModelIndex &/* index */) const +{ + editor->setGeometry(option.rect); +} + diff --git a/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.h b/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.h new file mode 100644 index 000000000..8329abb75 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.h @@ -0,0 +1,57 @@ +/** + ****************************************************************************** + * + * @file doublespindelegate.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief A double spinbox delegate + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef DOUBLESPINDELEGATE_H +#define DOUBLESPINDELEGATE_H + +#include +#include + +class DoubleSpinDelegate : public QItemDelegate +{ + Q_OBJECT + +public: + DoubleSpinDelegate(QObject *parent = 0); + + QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &option, + const QModelIndex &index) const; + + void setEditorData(QWidget *editor, const QModelIndex &index) const; + void setModelData(QWidget *editor, QAbstractItemModel *model, + const QModelIndex &index) const; + + void updateEditorGeometry(QWidget *editor, + const QStyleOptionViewItem &option, const QModelIndex &index) const; + +private: + double m_min; + double m_max; + double m_step; + int m_decimals; +}; + +#endif // DOUBLESPINDELEGATE_H diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 5a6f81895..7ca5b937b 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -7,7 +7,7 @@ 0 0 939 - 635 + 657 @@ -74,7 +74,7 @@ - 4 + 0 @@ -473,15 +473,15 @@ margin:1px; - - 0 - 0 + + 1 + 1 - 0 - 0 + 450 + 400 @@ -496,6 +496,12 @@ margin:1px; 10 + + + 300 + 300 + + @@ -1618,23 +1624,10 @@ margin:1px; - - - - Qt::Horizontal - - - - 40 - 20 - - - - - + 0 100 @@ -1676,6 +1669,12 @@ margin:1px; + + + 0 + 0 + + Rear throttle curve @@ -1775,7 +1774,7 @@ margin:1px; - + 1 1 @@ -1800,8 +1799,8 @@ margin:1px; - 200 - 200 + 300 + 350 @@ -1818,7 +1817,7 @@ margin:1px; - + 1 1 @@ -1843,8 +1842,8 @@ margin:1px; - 200 - 200 + 300 + 350 @@ -1941,6 +1940,16 @@ margin:1px; Ch 8 + + + Ch 9 + + + + + Ch 10 + + - @@ -2005,6 +2014,22 @@ margin:1px; AlignHCenter|AlignVCenter|AlignCenter + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + - @@ -2069,6 +2094,22 @@ margin:1px; AlignHCenter|AlignVCenter|AlignCenter + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + - @@ -2133,6 +2174,22 @@ margin:1px; AlignHCenter|AlignVCenter|AlignCenter + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + - @@ -2197,6 +2254,22 @@ margin:1px; AlignHCenter|AlignVCenter|AlignCenter + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + - @@ -2261,6 +2334,22 @@ margin:1px; AlignHCenter|AlignVCenter|AlignCenter + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + - @@ -2325,6 +2414,22 @@ margin:1px; AlignHCenter|AlignVCenter|AlignCenter + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + +
@@ -2747,7 +2852,7 @@ p, li { white-space: pre-wrap; } MixerCurve QWidget -
uavobjectwidgetutils/mixercurve.h
+
mixercurve.h
1
diff --git a/ground/openpilotgcs/src/plugins/config/ccpm.ui b/ground/openpilotgcs/src/plugins/config/ccpm.ui index 1ebb2a71b..6b0cc1d83 100644 --- a/ground/openpilotgcs/src/plugins/config/ccpm.ui +++ b/ground/openpilotgcs/src/plugins/config/ccpm.ui @@ -87,7 +87,7 @@ QGroupBox::title { } - 2 + 0 diff --git a/ground/openpilotgcs/src/plugins/config/config.pro b/ground/openpilotgcs/src/plugins/config/config.pro index 8e49cb54d..af38ef4ce 100644 --- a/ground/openpilotgcs/src/plugins/config/config.pro +++ b/ground/openpilotgcs/src/plugins/config/config.pro @@ -36,7 +36,9 @@ HEADERS += configplugin.h \ cfg_vehicletypes/configfixedwingwidget.h \ cfg_vehicletypes/vehicleconfig.h \ configrevowidget.h \ - config_global.h + config_global.h \ + mixercurve.h \ + doublespindelegate.h SOURCES += configplugin.cpp \ configgadgetconfiguration.cpp \ configgadgetwidget.cpp \ @@ -67,7 +69,9 @@ SOURCES += configplugin.cpp \ cfg_vehicletypes/configfixedwingwidget.cpp \ cfg_vehicletypes/configccpmwidget.cpp \ outputchannelform.cpp \ - cfg_vehicletypes/vehicleconfig.cpp + cfg_vehicletypes/vehicleconfig.cpp \ + mixercurve.cpp \ + doublespindelegate.cpp FORMS += airframe.ui \ cc_hw_settings.ui \ pro_hw_settings.ui \ @@ -83,5 +87,6 @@ FORMS += airframe.ui \ outputchannelform.ui \ revosensors.ui \ txpid.ui \ - pipxtreme.ui + pipxtreme.ui \ + mixercurve.ui RESOURCES += configgadget.qrc diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 640d3a6f9..764f8800b 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -165,14 +165,14 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); UAVObjectField* field = obj->getField(QString("Mixer1Type")); QStringList list = field->getOptions(); - for (int i=0;i<8;i++) { + for (int i=0; i<(int)(VehicleConfig::CHANNEL_NUMELEM); i++) { QComboBox* qb = new QComboBox(m_aircraft->customMixerTable); qb->addItems(list); m_aircraft->customMixerTable->setCellWidget(0,i,qb); } SpinBoxDelegate *sbd = new SpinBoxDelegate(); - for (int i=1;i<8; i++) { + for (int i=1; i<(int)(VehicleConfig::CHANNEL_NUMELEM); i++) { m_aircraft->customMixerTable->setItemDelegateForRow(i, sbd); } @@ -323,7 +323,7 @@ void ConfigVehicleTypeWidget::switchAirframeType(int index) m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio); if (m_aircraft->aircraftType->findText("Custom")) { m_aircraft->customMixerTable->resizeColumnsToContents(); - for (int i=0;i<8;i++) { + for (int i=0;i<(int)(VehicleConfig::CHANNEL_NUMELEM);i++) { m_aircraft->customMixerTable->setColumnWidth(i,(m_aircraft->customMixerTable->width()- m_aircraft->customMixerTable->verticalHeader()->width())/8); } @@ -342,7 +342,7 @@ void ConfigVehicleTypeWidget::showEvent(QShowEvent *event) // the result is usually a ahrsbargraph that is way too small. m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio); m_aircraft->customMixerTable->resizeColumnsToContents(); - for (int i=0;i<8;i++) { + for (int i=0;i<(int)(VehicleConfig::CHANNEL_NUMELEM);i++) { m_aircraft->customMixerTable->setColumnWidth(i,(m_aircraft->customMixerTable->width()- m_aircraft->customMixerTable->verticalHeader()->width())/8); } @@ -651,7 +651,7 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI() } // Update the mixer table: - for (int channel=0; channel<8; channel++) { + for (int channel=0; channel<(int)(VehicleConfig::CHANNEL_NUMELEM); channel++) { UAVObjectField* field = mixer->getField(mixerTypes.at(channel)); if (field) { @@ -721,7 +721,7 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets() vconfig->setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, m_aircraft->customThrottle2Curve->getCurve()); // Update the table: - for (int channel=0; channel<8; channel++) { + for (int channel=0; channel<(int)(VehicleConfig::CHANNEL_NUMELEM); channel++) { QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,channel); vconfig->setMixerType(mixer,channel, diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp similarity index 70% rename from ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp rename to ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 5eb62485a..28d5e66cc 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -1,5 +1,33 @@ +/** + ****************************************************************************** + * + * @file mixercurve.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief A MixerCurve Gadget used to update settings in the firmware + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + #include #include "mixercurve.h" +#include "doublespindelegate.h" MixerCurve::MixerCurve(QWidget *parent) : QFrame(parent), @@ -11,13 +39,18 @@ MixerCurve::MixerCurve(QWidget *parent) : m_curve = m_mixerUI->CurveWidget; m_settings = m_mixerUI->CurveSettings; - UpdateCurveSettings(); + DoubleSpinDelegate *sbd = new DoubleSpinDelegate(); + for (int i=0; isetItemDelegateForRow(i, sbd); + } - connect(m_mixerUI->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(UpdateCurveSettings())); + UpdateCurveUI(); + + connect(m_mixerUI->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(CurveTypeChanged())); connect(m_mixerUI->ResetCurve, SIGNAL(clicked()), this, SLOT(ResetCurve())); connect(m_mixerUI->GenerateCurve, SIGNAL(clicked()), this, SLOT(GenerateCurve())); - connect(m_curve, SIGNAL(curveUpdated()), this, SLOT(UpdateSettings())); - + connect(m_curve, SIGNAL(curveUpdated()), this, SLOT(UpdateSettingsTable())); + connect(m_settings, SIGNAL(itemChanged(QTableWidgetItem*)), this, SLOT(SettingsTableChanged())); connect(m_mixerUI->CurveMin, SIGNAL(valueChanged(double)), this, SLOT(CurveMinChanged(double))); connect(m_mixerUI->CurveMax, SIGNAL(valueChanged(double)), this, SLOT(CurveMaxChanged(double))); connect(m_mixerUI->CurveStep, SIGNAL(valueChanged(double)), this, SLOT(GenerateCurve())); @@ -35,19 +68,16 @@ void MixerCurve::setMixerType(MixerCurveType curveType) void MixerCurve::ResetCurve() { - m_curve->setMin((m_curveType == MixerCurve::MIXERCURVE_THROTTLE) ? 0.0 : -1.0); - m_curve->setMax(1.0); - m_mixerUI->CurveMin->setValue(m_curve->getMin()); m_mixerUI->CurveMax->setValue(m_curve->getMax()); m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Linear")); initLinearCurve(MixerCurveWidget::NODE_NUMELEM, m_curve->getMax(), m_curve->getMin()); - UpdateSettings(); + UpdateSettingsTable(); } -void MixerCurve::UpdateCurveSettings() +void MixerCurve::UpdateCurveUI() { //get the user settings QString curveType = m_mixerUI->CurveType->currentText(); @@ -60,7 +90,7 @@ void MixerCurve::UpdateCurveSettings() m_mixerUI->CurveStep->setMinimum(0.0); break; } - case MixerCurve::MIXERCURVEPITCH: + case MixerCurve::MIXERCURVE_PITCH: { m_mixerUI->CurveMin->setMinimum(-1.0); m_mixerUI->CurveMax->setMinimum(-1.0); @@ -68,8 +98,8 @@ void MixerCurve::UpdateCurveSettings() break; } } - m_mixerUI->CurveMin->setMaximum(1.0); - m_mixerUI->CurveMax->setMaximum(1.0); + m_mixerUI->CurveMin->setMaximum(m_curve->getMax()); + m_mixerUI->CurveMax->setMaximum(m_curve->getMax()); m_mixerUI->CurveStep->setMaximum(100.0); //set default visible @@ -168,50 +198,56 @@ void MixerCurve::GenerateCurve() } } - initCurve(&points); + setCurve(&points); } +/** + Wrappers for mixercurvewidget. + */ void MixerCurve::initCurve (const QList* points) { m_curve->setCurve(points); - UpdateSettings(); + UpdateSettingsTable(); } - QList MixerCurve::getCurve() { return m_curve->getCurve(); } - void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue) { + setMin(minValue); + setMax(maxValue); + m_curve->initLinearCurve(numPoints, maxValue, minValue); } - void MixerCurve::setCurve(const QList* points) { m_curve->setCurve(points); - UpdateSettings(); + UpdateSettingsTable(); } - void MixerCurve::setMin(double value) { m_curve->setMin(value); + m_mixerUI->CurveMin->setMinimum(value); } - double MixerCurve::getMin() { return m_curve->getMin(); } - void MixerCurve::setMax(double value) { m_curve->setMax(value); + m_mixerUI->CurveMax->setMaximum(value); } - double MixerCurve::getMax() { return m_curve->getMax(); } +double MixerCurve::setRange(double min, double max) +{ + return m_curve->setRange(min, max); +} + double MixerCurve::getCurveMin() { @@ -227,26 +263,48 @@ double MixerCurve::getCurveStep() return m_mixerUI->CurveStep->value(); } -void MixerCurve::UpdateSettings() +void MixerCurve::UpdateSettingsTable() { QList points = m_curve->getCurve(); - int ptCnt = points.count(); + for (int i=0; iitem((ptCnt - 1) - i, 0); + QTableWidgetItem* item = m_settings->item(i, 0); if (item) - item->setText(QString().sprintf("%.2f",points.at(i))); + item->setText(QString().sprintf("%.2f",points.at( (ptCnt - 1) - i ))); } } +void MixerCurve::SettingsTableChanged() +{ + QList points; + + for (int i=0; i < m_settings->rowCount(); i++) + { + QTableWidgetItem* item = m_settings->item(i, 0); + + if (item) + points.push_front(item->text().toDouble()); + } + + m_curve->setCurve(&points); +} + +void MixerCurve::CurveTypeChanged() +{ + // setup the ui for this curvetype + UpdateCurveUI(); + + // and generate a curve based on the selection + GenerateCurve(); +} + void MixerCurve::CurveMinChanged(double value) { - //setMin(value); - // the min changed so redraw the curve // mixercurvewidget::setCurve will trim any points below min - QList points = getCurve(); + QList points = m_curve->getCurve(); points.removeFirst(); points.push_front(value); setCurve(&points); @@ -254,21 +312,14 @@ void MixerCurve::CurveMinChanged(double value) void MixerCurve::CurveMaxChanged(double value) { - //setMax(value); - // the max changed so redraw the curve // mixercurvewidget::setCurve will trim any points above max - QList points = getCurve(); + QList points = m_curve->getCurve(); points.removeLast(); points.append(value); setCurve(&points); } -double MixerCurve::setRange(double min, double max) -{ - return m_curve->setRange(min, max); -} - void MixerCurve::showEvent(QShowEvent *event) { Q_UNUSED(event); diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.h b/ground/openpilotgcs/src/plugins/config/mixercurve.h new file mode 100644 index 000000000..3133da660 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.h @@ -0,0 +1,97 @@ +/** + ****************************************************************************** + * + * @file mixercurve.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief A MixerCurve Gadget used to update settings in the firmware + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef MIXERCURVE_H +#define MIXERCURVE_H + +#include +#include +#include +#include + +#include "ui_mixercurve.h" +#include "mixercurvewidget.h" +#include "uavobjectwidgetutils_global.h" + + +namespace Ui { +class MixerCurve; +} + +class MixerCurve : public QFrame +{ + Q_OBJECT + +public: + explicit MixerCurve(QWidget *parent = 0); + ~MixerCurve(); + + + /* Enumeration options for ThrottleCurves */ + typedef enum { MIXERCURVE_THROTTLE=0, MIXERCURVE_PITCH=1 } MixerCurveType; + + void setMixerType(MixerCurveType curveType); + void initCurve (const QList* points); + QList getCurve(); + void initLinearCurve(int numPoints, double maxValue = 1, double minValue = 0); + void setCurve(const QList* points); + void setMin(double value); + double getMin(); + void setMax(double value); + double getMax(); + double getCurveMin(); + double getCurveMax(); + double getCurveStep(); + double setRange(double min, double max); + + +signals: + +protected: + void showEvent(QShowEvent *event); + void resizeEvent(QResizeEvent *event); + +public slots: + void ResetCurve(); + void GenerateCurve(); + void UpdateSettingsTable(); + +private slots: + void SettingsTableChanged(); + void CurveTypeChanged(); + void CurveMinChanged(double value); + void CurveMaxChanged(double value); + void UpdateCurveUI(); + +private: + Ui::MixerCurve* m_mixerUI; + MixerCurveWidget* m_curve; + QTableWidget* m_settings; + MixerCurveType m_curveType; + +}; + +#endif // MIXERCURVE_H diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.ui b/ground/openpilotgcs/src/plugins/config/mixercurve.ui new file mode 100644 index 000000000..65dbdc5f9 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.ui @@ -0,0 +1,378 @@ + + + MixerCurve + + + + 0 + 0 + 355 + 272 + + + + + 1 + 1 + + + + + 200 + 200 + + + + + 500 + 500 + + + + + 300 + 300 + + + + MixerCurve + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + 90 + 0 + 261 + 231 + + + + + QLayout::SetMinAndMaxSize + + + + + + 1 + 1 + + + + + 50 + 50 + + + + + 1000 + 1000 + + + + + 10 + 10 + + + + + 200 + 200 + + + + + + + + + + 0 + 0 + 91 + 271 + + + + + + 0 + 0 + 87 + 171 + + + + + 8 + + + + Qt::ScrollBarAlwaysOff + + + Qt::ScrollBarAlwaysOff + + + false + + + true + + + 5 + + + 1 + + + + 5 + + + + + 4 + + + + + 3 + + + + + 2 + + + + + 1 + + + + + Value + + + + + 1.0 + + + + + .75 + + + + + .50 + + + + + .25 + + + + + .00 + + + + + + + 0 + 180 + 87 + 20 + + + + + Linear + + + + + Log + + + + + Exp + + + + + Flat + + + + + Step + + + + + + + 0 + 200 + 87 + 23 + + + + Generate + + + + + + 0 + 240 + 87 + 23 + + + + Reset + + + + + + + 100 + 230 + 61 + 16 + + + + Min + + + + + + 100 + 250 + 61 + 20 + + + + QAbstractSpinBox::CorrectToNearestValue + + + -1.000000000000000 + + + 1.000000000000000 + + + 0.010000000000000 + + + 0.000000000000000 + + + + + + 240 + 230 + 87 + 13 + + + + Step + + + + + + 240 + 250 + 61 + 20 + + + + QAbstractSpinBox::CorrectToNearestValue + + + 50.000000000000000 + + + + + + 170 + 230 + 51 + 16 + + + + Max + + + + + + 170 + 250 + 61 + 20 + + + + QAbstractSpinBox::CorrectToNearestValue + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.010000000000000 + + + 1.000000000000000 + + + groupBox + verticalGroupBox + minLabel + CurveMin + stepLabel + CurveStep + maxLabel + CurveMax + + + + MixerCurveWidget + QWidget +
uavobjectwidgetutils/mixercurvewidget.h
+ 1 +
+
+ + +
diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h deleted file mode 100644 index faa326109..000000000 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.h +++ /dev/null @@ -1,68 +0,0 @@ -#ifndef MIXERCURVE_H -#define MIXERCURVE_H - -#include -#include -#include -#include - -#include "ui_mixercurve.h" -#include "mixercurvewidget.h" -#include "uavobjectwidgetutils_global.h" - -namespace Ui { -class MixerCurve; -} - -class UAVOBJECTWIDGETUTILS_EXPORT MixerCurve : public QFrame -{ - Q_OBJECT - -public: - explicit MixerCurve(QWidget *parent = 0); - ~MixerCurve(); - - - /* Enumeration options for ThrottleCurves */ - typedef enum { MIXERCURVE_THROTTLE=0, MIXERCURVEPITCH=1 } MixerCurveType; - - void setMixerType(MixerCurveType curveType); - void initCurve (const QList* points); - QList getCurve(); - void initLinearCurve(int numPoints, double maxValue = 1, double minValue = 0); - void setCurve(const QList* points); - void setMin(double value); - double getMin(); - void setMax(double value); - double getMax(); - double getCurveMin(); - double getCurveMax(); - double getCurveStep(); - double setRange(double min, double max); - - -signals: - -protected: - void showEvent(QShowEvent *event); - void resizeEvent(QResizeEvent *event); - -public slots: - void ResetCurve(); - void GenerateCurve(); - void UpdateSettings(); - -private slots: - void CurveMinChanged(double value); - void CurveMaxChanged(double value); - void UpdateCurveSettings(); - -private: - Ui::MixerCurve* m_mixerUI; - MixerCurveWidget* m_curve; - QTableWidget* m_settings; - MixerCurveType m_curveType; - -}; - -#endif // MIXERCURVE_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui deleted file mode 100644 index 0ef6f3d80..000000000 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurve.ui +++ /dev/null @@ -1,303 +0,0 @@ - - - MixerCurve - - - - 0 - 0 - 490 - 390 - - - - - 1 - 1 - - - - - 442 - 328 - - - - - 500 - 500 - - - - - 300 - 300 - - - - MixerCurve - - - QFrame::StyledPanel - - - QFrame::Raised - - - - - 120 - 0 - 371 - 391 - - - - - - - - 1 - 1 - - - - - 50 - 50 - - - - - 1000 - 1000 - - - - - 10 - 10 - - - - - 200 - 200 - - - - - - - - - - 0 - 0 - 121 - 391 - - - - - - - - Linear - - - - - Log - - - - - Exp - - - - - Flat - - - - - Step - - - - - - - - Generate - - - - - - - Max - - - - - - - QAbstractSpinBox::CorrectToNearestValue - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.010000000000000 - - - 1.000000000000000 - - - - - - - - 8 - - - - Qt::ScrollBarAlwaysOff - - - Qt::ScrollBarAlwaysOff - - - false - - - 5 - - - 1 - - - - 5 - - - - - 4 - - - - - 3 - - - - - 2 - - - - - 1 - - - - - Value - - - - - 1.0 - - - - - .75 - - - - - .50 - - - - - .25 - - - - - .00 - - - - - - - - Min - - - - - - - QAbstractSpinBox::CorrectToNearestValue - - - -1.000000000000000 - - - 1.000000000000000 - - - 0.010000000000000 - - - 0.000000000000000 - - - - - - - Step - - - - - - - QAbstractSpinBox::CorrectToNearestValue - - - - - - - Reset - - - - - - - - - MixerCurveWidget - QWidget -
uavobjectwidgetutils/mixercurvewidget.h
- 1 -
-
- - -
diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutils.pro b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutils.pro index e4a0fee99..475526325 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutils.pro +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutils.pro @@ -10,18 +10,15 @@ HEADERS += uavobjectwidgetutils_global.h \ mixercurvewidget.h \ mixercurvepoint.h \ mixercurveline.h \ - smartsavebutton.h \ - mixercurve.h + smartsavebutton.h SOURCES += uavobjectwidgetutilsplugin.cpp \ configtaskwidget.cpp \ mixercurvewidget.cpp \ mixercurvepoint.cpp \ mixercurveline.cpp \ - smartsavebutton.cpp \ - mixercurve.cpp + smartsavebutton.cpp OTHER_FILES += UAVObjectWidgetUtils.pluginspec -FORMS += \ - mixercurve.ui +FORMS += From 23aea6eac482b3892e0f472f5b4b275ce61c6aee Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Thu, 5 Jul 2012 12:58:00 -0700 Subject: [PATCH 006/543] MixerCurve: integrated into all airframes. --- .../openpilotgcs/src/plugins/config/ccpm.ui | 548 +-------------- .../cfg_vehicletypes/configccpmwidget.cpp | 319 +-------- .../cfg_vehicletypes/configccpmwidget.h | 5 - .../config/configvehicletypewidget.cpp | 7 - .../src/plugins/config/mixercurve.cpp | 10 +- .../src/plugins/config/mixercurve.ui | 654 +++++++++--------- .../uavobjectwidgetutils/mixercurvepoint.cpp | 4 +- 7 files changed, 373 insertions(+), 1174 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/ccpm.ui b/ground/openpilotgcs/src/plugins/config/ccpm.ui index 6b0cc1d83..ee28ad4f0 100644 --- a/ground/openpilotgcs/src/plugins/config/ccpm.ui +++ b/ground/openpilotgcs/src/plugins/config/ccpm.ui @@ -2770,537 +2770,13 @@ margin:1px; 3 - - - - - - 150 - 0 - - - - - 10 - - - - Select aircraft type here - - - - Linear - - - - - Flat - - - - - Step - - - - - Exp - - - - - Log - - - - - Custom - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - Number of points - - - - - - - - 0 - 0 - - - - 2 - - - 10 - - - 5 - - - - + - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Min - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Max - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Step point - - - - - - - 1 - - - 10.000000000000000 - - - - - - - 1 - - - 10.000000000000000 - - - 1.000000000000000 - - - - - - - 1 - - - 100.000000000000000 - - - 50.000000000000000 - - - - - - - - - - - - 0 - 0 - - - - - 150 - 0 - - - - - 10 - - - - Select aircraft type here - - - - Throttle - - - - - Pitch - - - - - - - - - 0 - 0 - - - - - 150 - 0 - - - - Generate curves based on settings - - - <-- Generate Curve - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - 3 - - - - - 0 - 0 - - - - - 250 - 200 - - - - - 250 - 273 - - - - Qt::ScrollBarAsNeeded - - - Qt::ScrollBarAsNeeded - - - true - - - true - - - true - - - true - - - true - - - 25 - - - 25 - - - - 0% - - - - - 25% - - - - - 50% - - - - - 75% - - - - - 100% - - - - - none - - - - - none - - - - - none - - - - - none - - - - - none - - - - - Throttle Curve - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - Blade Pitch Curve - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - 0.000 - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - 0.000 - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - 0.250 - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - 0.250 - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - 0.500 - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - 0.500 - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - 0.750 - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - 0.750 - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - 1.000 - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - 1.000 - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - @@ -3331,7 +2807,7 @@ margin:1px; Qt::LeftToRight - Throttle Curve + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -3347,7 +2823,7 @@ margin:1px; 0 - + 1 @@ -3410,7 +2886,7 @@ margin:1px; - Pitch Curve + @@ -3420,7 +2896,7 @@ margin:1px; 0 - + 1 @@ -3458,7 +2934,7 @@ margin:1px; - + Qt::Vertical @@ -3910,9 +3386,9 @@ margin:1px; - MixerCurveWidget + MixerCurve QWidget -
uavobjectwidgetutils/mixercurvewidget.h
+
mixercurve.h
1
@@ -3945,14 +3421,6 @@ margin:1px; SwashLvlPositionSlider SwashLvlPositionSpinBox SwashLvlSwashplateImage - CurveType - NumCurvePoints - CurveValue1 - CurveValue2 - CurveValue3 - CurveToGenerate - ccpmGenerateCurve - CurveSettings ccpmAdvancedSettingsTable diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp index e7ca51fd1..86879ec38 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp @@ -133,9 +133,13 @@ ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) : VehicleConfig(parent) } //initialize our two mixer curves - m_ccpm->PitchCurve->initLinearCurve(5, 1.0, -1.0); + + m_ccpm->ThrottleCurve->setMixerType(MixerCurve::MIXERCURVE_THROTTLE); m_ccpm->ThrottleCurve->initLinearCurve(5, 1.0); + m_ccpm->PitchCurve->setMixerType(MixerCurve::MIXERCURVE_PITCH); + m_ccpm->PitchCurve->initLinearCurve(5, 1.0, -1.0); + //initialize channel names m_ccpm->ccpmEngineChannel->addItems(channelNames); m_ccpm->ccpmEngineChannel->setCurrentIndex(0); @@ -158,22 +162,10 @@ ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) : VehicleConfig(parent) m_ccpm->ccpmType->addItems(Types); m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->count() - 1); - UpdateCurveSettings(); - - //disable changing number of points in curves until UAVObjects have more than 5 - m_ccpm->NumCurvePoints->setEnabled(0); - refreshWidgetsValues(QString("HeliCP")); UpdateType(); - //connect(m_ccpm->saveccpmToSD, SIGNAL(clicked()), this, SLOT(saveccpmUpdate())); - //connect(m_ccpm->saveccpmToRAM, SIGNAL(clicked()), this, SLOT(sendccpmUpdate())); - //connect(m_ccpm->getccpmCurrent, SIGNAL(clicked()), this, SLOT(requestccpmUpdate())); - connect(m_ccpm->ccpmGenerateCurve, SIGNAL(clicked()), this, SLOT(GenerateCurve())); - connect(m_ccpm->NumCurvePoints, SIGNAL(valueChanged(int)), this, SLOT(UpdateCurveSettings())); - connect(m_ccpm->CurveToGenerate, SIGNAL(currentIndexChanged(int)), this, SLOT(UpdateCurveSettings())); - connect(m_ccpm->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(UpdateCurveSettings())); connect(m_ccpm->ccpmAngleW, SIGNAL(valueChanged(double)), this, SLOT(ccpmSwashplateUpdate())); connect(m_ccpm->ccpmAngleX, SIGNAL(valueChanged(double)), this, SLOT(ccpmSwashplateUpdate())); connect(m_ccpm->ccpmAngleY, SIGNAL(valueChanged(double)), this, SLOT(ccpmSwashplateUpdate())); @@ -191,12 +183,8 @@ ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) : VehicleConfig(parent) connect(m_ccpm->ccpmCollectivespinBox, SIGNAL(valueChanged(int)), this, SLOT(UpdateMixer())); connect(m_ccpm->ccpmType, SIGNAL(currentIndexChanged(int)), this, SLOT(UpdateType())); connect(m_ccpm->ccpmSingleServo, SIGNAL(currentIndexChanged(int)), this, SLOT(UpdateType())); - connect(m_ccpm->CurveSettings, SIGNAL(cellChanged (int, int)), this, SLOT(UpdateCurveWidgets())); connect(m_ccpm->TabObject, SIGNAL(currentChanged ( QWidget * )), this, SLOT(UpdateType())); - connect(m_ccpm->PitchCurve, SIGNAL(curveUpdated(QList,double)), this, SLOT(updatePitchCurveValue(QList,double))); - connect(m_ccpm->ThrottleCurve, SIGNAL(curveUpdated(QList,double)), this, SLOT(updateThrottleCurveValue(QList,double))); - connect(m_ccpm->SwashLvlStartButton, SIGNAL(clicked()), this, SLOT(SwashLvlStartButtonPressed())); connect(m_ccpm->SwashLvlNextButton, SIGNAL(clicked()), this, SLOT(SwashLvlNextButtonPressed())); connect(m_ccpm->SwashLvlCancelButton, SIGNAL(clicked()), this, SLOT(SwashLvlCancelButtonPressed())); @@ -332,8 +320,6 @@ void ConfigCcpmWidget::UpdateType() AdjustmentAngle=SingleServoIndex*90; - m_ccpm->CurveToGenerate->setEnabled(1); - m_ccpm->CurveSettings->setColumnHidden(1,0); m_ccpm->PitchCurve->setVisible(1); //m_ccpm->customThrottleCurve2Value->setVisible(1); //m_ccpm->label_41->setVisible(1); @@ -425,9 +411,6 @@ void ConfigCcpmWidget::UpdateType() m_ccpm->ccpmCollectiveSlider->setEnabled(0); m_ccpm->ccpmCollectivespinBox->setValue(0); m_ccpm->ccpmCollectiveSlider->setValue(0); - m_ccpm->CurveToGenerate->setCurrentIndex(0); - m_ccpm->CurveToGenerate->setEnabled(0); - m_ccpm->CurveSettings->setColumnHidden(1,1); m_ccpm->PitchCurve->setVisible(0); //m_ccpm->customThrottleCurve2Value->setVisible(0); //m_ccpm->label_41->setVisible(0); @@ -469,271 +452,7 @@ void ConfigCcpmWidget::UpdateType() } -void ConfigCcpmWidget::UpdateCurveWidgets() -{ - int NumCurvePoints,i,Changed; - QList curveValues; - QList OldCurveValues; - double ThisValue; - //get the user settings - NumCurvePoints=m_ccpm->NumCurvePoints->value(); - curveValues.clear(); - Changed=0; - OldCurveValues=m_ccpm->ThrottleCurve->getCurve(); - for (i=0; iCurveSettings->item(i, 0 )->text().toDouble(); - curveValues.append(ThisValue); - if (ThisValue!=OldCurveValues.at(i))Changed=1; - } - // Setup all Throttle1 curves for all types of airframes - if (Changed==1) - m_ccpm->ThrottleCurve->setCurve(&curveValues); - - curveValues.clear(); - Changed=0; - OldCurveValues=m_ccpm->PitchCurve->getCurve(); - for (i=0; iCurveSettings->item(i, 1 )->text().toDouble(); - curveValues.append(ThisValue); - if (ThisValue!=OldCurveValues.at(i))Changed=1; - } - // Setup all Throttle1 curves for all types of airframes - if (Changed==1) - m_ccpm->PitchCurve->setCurve(&curveValues); -} - -void ConfigCcpmWidget::updatePitchCurveValue(QList curveValues0,double Value0) -{ - Q_UNUSED(curveValues0); - Q_UNUSED(Value0); - - int NumCurvePoints,i; - double CurrentValue; - QList internalCurveValues; - //get the user settings - NumCurvePoints=m_ccpm->NumCurvePoints->value(); - internalCurveValues=m_ccpm->PitchCurve->getCurve(); - - for (i=0; iCurveSettings->item(i, 1 )->text().toDouble(); - if (CurrentValue!=internalCurveValues[i]) - { - m_ccpm->CurveSettings->item(i, 1)->setText(QString().sprintf("%.3f",internalCurveValues.at(i))); - } - - } - -} - -void ConfigCcpmWidget::updateThrottleCurveValue(QList curveValues0,double Value0) -{ - Q_UNUSED(curveValues0); - Q_UNUSED(Value0); - - int NumCurvePoints,i; - double CurrentValue; - QList internalCurveValues; - //get the user settings - NumCurvePoints=m_ccpm->NumCurvePoints->value(); - internalCurveValues=m_ccpm->ThrottleCurve->getCurve(); - - for (i=0; iCurveSettings->item(i, 0 )->text().toDouble(); - if (CurrentValue!=internalCurveValues[i]) - { - m_ccpm->CurveSettings->item(i, 0)->setText(QString().sprintf("%.3f",internalCurveValues.at(i))); - } - - } - -} - - -void ConfigCcpmWidget::UpdateCurveSettings() -{ - int NumCurvePoints,i; - double scale; - QString CurveType; - QStringList vertHeaders; - - //get the user settings - NumCurvePoints=m_ccpm->NumCurvePoints->value(); - CurveType=m_ccpm->CurveType->currentText(); - - vertHeaders << "-" << "-" << "-" << "-" << "-" << "-" << "-" << "-" << "-" << "-" ; - for (i=0;iCurveSettings->setVerticalHeaderLabels( vertHeaders ); - - if (m_ccpm->CurveToGenerate->currentIndex()==0) - { - m_ccpm->CurveValue1->setMinimum(0.0); - m_ccpm->CurveValue2->setMinimum(0.0); - m_ccpm->CurveValue3->setMinimum(0.0); - } - else - { - m_ccpm->CurveValue1->setMinimum(-1.0); - m_ccpm->CurveValue2->setMinimum(-1.0); - m_ccpm->CurveValue3->setMinimum(0.0); - } - m_ccpm->CurveValue1->setMaximum(1.0); - m_ccpm->CurveValue2->setMaximum(1.0); - m_ccpm->CurveValue3->setMaximum(100.0); - m_ccpm->CurveValue1->setSingleStep(0.1); - m_ccpm->CurveValue2->setSingleStep(0.1); - m_ccpm->CurveValue3->setSingleStep(1.0); - m_ccpm->CurveValue1->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue);; - m_ccpm->CurveValue2->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue); - m_ccpm->CurveValue3->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue); - - //set default visible - m_ccpm->CurveLabel1->setVisible(true); - m_ccpm->CurveValue1->setVisible(true); - m_ccpm->CurveLabel2->setVisible(false); - m_ccpm->CurveValue2->setVisible(false); - m_ccpm->CurveLabel3->setVisible(false); - m_ccpm->CurveValue3->setVisible(false); - m_ccpm->ccpmGenerateCurve->setVisible(true); - m_ccpm->CurveToGenerate->setVisible(true); - - if ( CurveType.compare("Flat")==0) - { - m_ccpm->CurveLabel1->setText("Value"); - } - if ( CurveType.compare("Linear")==0) - { - m_ccpm->CurveLabel1->setText("Min"); - m_ccpm->CurveLabel2->setText("Max"); - m_ccpm->CurveLabel2->setVisible(true); - m_ccpm->CurveValue2->setVisible(true); - } - if ( CurveType.compare("Step")==0) - { - m_ccpm->CurveLabel1->setText("Min"); - m_ccpm->CurveLabel2->setText("Max"); - m_ccpm->CurveLabel2->setVisible(true); - m_ccpm->CurveValue2->setVisible(true); - m_ccpm->CurveLabel3->setText("Step at"); - m_ccpm->CurveLabel3->setVisible(true); - m_ccpm->CurveValue3->setVisible(true); - } - if ( CurveType.compare("Exp")==0) - { - m_ccpm->CurveLabel1->setText("Min"); - m_ccpm->CurveLabel2->setText("Max"); - m_ccpm->CurveLabel2->setVisible(true); - m_ccpm->CurveValue2->setVisible(true); - m_ccpm->CurveLabel3->setText("Strength"); - m_ccpm->CurveLabel3->setVisible(true); - m_ccpm->CurveValue3->setVisible(true); - m_ccpm->CurveValue3->setMinimum(1.0); - m_ccpm->CurveValue3->setMaximum(100.0); - m_ccpm->CurveValue3->setSingleStep(1.0); - m_ccpm->CurveValue3->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue);; - } - if ( CurveType.compare("Log")==0) - { - m_ccpm->CurveLabel1->setText("Min"); - m_ccpm->CurveLabel2->setText("Max"); - m_ccpm->CurveLabel2->setVisible(true); - m_ccpm->CurveValue2->setVisible(true); - m_ccpm->CurveLabel3->setText("Strength"); - m_ccpm->CurveLabel3->setVisible(true); - m_ccpm->CurveValue3->setVisible(true); - m_ccpm->CurveValue3->setMinimum(1.0); - m_ccpm->CurveValue3->setMaximum(100.0); - m_ccpm->CurveValue3->setSingleStep(1.0); - m_ccpm->CurveValue3->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue); - } - if ( CurveType.compare("Custom")==0) - { - m_ccpm->CurveLabel1->setVisible(false); - m_ccpm->CurveValue1->setVisible(false); - m_ccpm->ccpmGenerateCurve->setVisible(false); - m_ccpm->CurveToGenerate->setVisible(false); - } - - UpdateCurveWidgets(); - -} -void ConfigCcpmWidget::GenerateCurve() -{ - int NumCurvePoints,CurveToGenerate,i; - double value1, value2, value3, scale; - QString CurveType; - QTableWidgetItem *item; - double newValue; - - - //get the user settings - NumCurvePoints=m_ccpm->NumCurvePoints->value(); - value1=m_ccpm->CurveValue1->value(); - value2=m_ccpm->CurveValue2->value(); - value3=m_ccpm->CurveValue3->value(); - CurveToGenerate=m_ccpm->CurveToGenerate->currentIndex(); - CurveType=m_ccpm->CurveType->currentText(); - - - - for (i=0;iCurveSettings->item(i, CurveToGenerate ); - - if ( CurveType.compare("Flat")==0) - { - //item->setText( tr( "%1" ).arg( value1 ) ); - item->setText(QString().sprintf("%.3f",value1)); - } - if ( CurveType.compare("Linear")==0) - { - newValue =value1 +(scale*(value2-value1)); - //item->setText( tr( "%1" ).arg(value1 +(scale*(value2-value1))) ); - item->setText(QString().sprintf("%.3f",newValue)); - } - if ( CurveType.compare("Step")==0) - { - if (scale*100setText( tr( "%1" ).arg(value1) ); - item->setText(QString().sprintf("%.3f",value1)); - } - else - { - //item->setText( tr( "%1" ).arg(value2) ); - item->setText(QString().sprintf("%.3f",value2)); - } - } - if ( CurveType.compare("Exp")==0) - { - newValue =value1 +(((exp(scale*(value3/10))-1))/(exp((value3/10))-1)*(value2-value1)); - //item->setText( tr( "%1" ).arg(value1 +(((exp(scale*(value3/10))-1))/(exp((value3/10))-1)*(value2-value1))) ); - item->setText(QString().sprintf("%.3f",newValue)); - } - if ( CurveType.compare("Log")==0) - { - newValue = value1 +(((log(scale*(value3*2)+1))/(log(1+(value3*2))))*(value2-value1)); - //item->setText( tr( "%1" ).arg(value1 +(((log(scale*(value3*2)+1))/(log(1+(value3*2))))*(value2-value1))) ); - item->setText(QString().sprintf("%.3f",newValue)); - } - } - for (i=NumCurvePoints;i<10;i++) - { - item =m_ccpm->CurveSettings->item(i, CurveToGenerate ); - item->setText( tr( "" ) ); - } - UpdateCurveWidgets(); - -} void ConfigCcpmWidget::ccpmSwashplateRedraw() { @@ -1111,22 +830,20 @@ void ConfigCcpmWidget::getMixer() { if (SwashLvlConfigurationInProgress)return; if (updatingToHardware)return; + updatingFromHardware=TRUE; - int i; + UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); - // Get existing mixer settings - MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); - MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); + QPointer vconfig = new VehicleConfig(); - //get the settings for the curve from the mixer settings - for (i=0;i<5;i++) - { - m_ccpm->CurveSettings->item(i, 0)->setText(QString().sprintf("%.3f", - mixerSettingsData.ThrottleCurve1[i])); - m_ccpm->CurveSettings->item(i, 1)->setText(QString().sprintf("%.3f", - mixerSettingsData.ThrottleCurve2[i])); - } + QList curveValues; + vconfig->getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, &curveValues); + m_ccpm->ThrottleCurve->setCurve(&curveValues); + + vconfig->getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, &curveValues); + m_ccpm->PitchCurve->setCurve(&curveValues); updatingFromHardware=FALSE; @@ -1195,9 +912,11 @@ void ConfigCcpmWidget::setMixer() } //get the user data for the curve into the mixer settings + QList curve1 = m_ccpm->ThrottleCurve->getCurve(); + QList curve2 = m_ccpm->PitchCurve->getCurve(); for (i=0;i<5;i++) { - mixerSettingsData.ThrottleCurve1[i] = m_ccpm->CurveSettings->item(i, 0)->text().toDouble(); - mixerSettingsData.ThrottleCurve2[i] = m_ccpm->CurveSettings->item(i, 1)->text().toDouble(); + mixerSettingsData.ThrottleCurve1[i] = curve1.at(i); + mixerSettingsData.ThrottleCurve2[i] = curve2.at(i); } //mapping of collective input to curve 2... diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h index 56161c36f..5e59a946f 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h @@ -99,13 +99,8 @@ private: void ccpmSwashplateUpdate(); void ccpmSwashplateRedraw(); - void UpdateCurveSettings(); - void GenerateCurve(); void UpdateMixer(); void UpdateType(); - void UpdateCurveWidgets(); - void updatePitchCurveValue(QList,double); - void updateThrottleCurveValue(QList,double); void SwashLvlStartButtonPressed(); void SwashLvlNextButtonPressed(); diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 764f8800b..c356bd0b3 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -841,13 +841,6 @@ void ConfigVehicleTypeWidget::addToDirtyMonitor() addWidget(m_heli->m_ccpm->ccpmRollScaleBox); addWidget(m_heli->m_ccpm->SwashLvlPositionSlider); addWidget(m_heli->m_ccpm->SwashLvlPositionSpinBox); - addWidget(m_heli->m_ccpm->CurveType); - addWidget(m_heli->m_ccpm->NumCurvePoints); - addWidget(m_heli->m_ccpm->CurveValue1); - addWidget(m_heli->m_ccpm->CurveValue2); - addWidget(m_heli->m_ccpm->CurveValue3); - addWidget(m_heli->m_ccpm->CurveToGenerate); - addWidget(m_heli->m_ccpm->CurveSettings); addWidget(m_heli->m_ccpm->ThrottleCurve); addWidget(m_heli->m_ccpm->PitchCurve); addWidget(m_heli->m_ccpm->ccpmAdvancedSettingsTable); diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 28d5e66cc..76dd6da23 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -64,6 +64,7 @@ MixerCurve::~MixerCurve() void MixerCurve::setMixerType(MixerCurveType curveType) { m_curveType = curveType; + m_mixerUI->CurveGroup->setTitle( (m_curveType == MixerCurve::MIXERCURVE_THROTTLE) ? "Throttle Curve" : "Pitch Curve"); } void MixerCurve::ResetCurve() @@ -87,19 +88,19 @@ void MixerCurve::UpdateCurveUI() { m_mixerUI->CurveMin->setMinimum(0.0); m_mixerUI->CurveMax->setMinimum(0.0); - m_mixerUI->CurveStep->setMinimum(0.0); break; } case MixerCurve::MIXERCURVE_PITCH: { m_mixerUI->CurveMin->setMinimum(-1.0); m_mixerUI->CurveMax->setMinimum(-1.0); - m_mixerUI->CurveStep->setMinimum(0.0); break; } } m_mixerUI->CurveMin->setMaximum(m_curve->getMax()); m_mixerUI->CurveMax->setMaximum(m_curve->getMax()); + + m_mixerUI->CurveStep->setMinimum(0.0); m_mixerUI->CurveStep->setMaximum(100.0); //set default visible @@ -135,6 +136,8 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->stepLabel->setText("Strength"); m_mixerUI->stepLabel->setVisible(true); m_mixerUI->CurveStep->setVisible(true); + + m_mixerUI->CurveStep->setMinimum(1.0); } if ( curveType.compare("Log")==0) { @@ -142,7 +145,8 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->CurveMax->setVisible(true); m_mixerUI->stepLabel->setText("Strength"); m_mixerUI->stepLabel->setVisible(true); - m_mixerUI->CurveStep->setVisible(true); + m_mixerUI->CurveStep->setVisible(true); + m_mixerUI->CurveStep->setMinimum(1.0); } GenerateCurve(); diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.ui b/ground/openpilotgcs/src/plugins/config/mixercurve.ui index 65dbdc5f9..e174a333f 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.ui +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.ui @@ -6,8 +6,8 @@ 0 0 - 355 - 272 + 447 + 321 @@ -24,8 +24,8 @@ - 500 - 500 + 1000 + 1000 @@ -43,327 +43,349 @@ QFrame::Raised - + - 90 - 0 - 261 - 231 + 10 + 10 + 422 + 301 - - - QLayout::SetMinAndMaxSize - - - - - - 1 - 1 - + + + + + QLayout::SetDefaultConstraint - - - 50 - 50 - + + + + + 100 + 16777215 + + + + Throttle Curve + + + + + + + 71 + 200 + + + + + 8 + + + + Qt::ScrollBarAlwaysOff + + + Qt::ScrollBarAlwaysOff + + + false + + + true + + + 5 + + + 1 + + + + 5 + + + + + 4 + + + + + 3 + + + + + 2 + + + + + 1 + + + + + Value + + + AlignJustify|AlignVCenter + + + + + 1.0 + + + + + .75 + + + + + .50 + + + + + .25 + + + + + .00 + + + + + + + + + Linear + + + + + Log + + + + + Exp + + + + + Flat + + + + + Step + + + + + + + + Generate + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + Reset + + + + + GenerateCurve + CurveSettings + ResetCurve + CurveType + verticalSpacer + + + + + + + + QLayout::SetDefaultConstraint - - - 1000 - 1000 - - - - - 10 - 10 - - - - - 200 - 200 - - - + + + + + 1 + 1 + + + + + QLayout::SetMinAndMaxSize + + + + + + 5 + 5 + + + + + 50 + 50 + + + + + 1000 + 1000 + + + + + 10 + 10 + + + + + 200 + 200 + + + + + 7 + + + CurveGroup + + + + + + + + + + + + + + Min + + + + + + + QAbstractSpinBox::CorrectToNearestValue + + + -1.000000000000000 + + + 1.000000000000000 + + + 0.010000000000000 + + + 0.000000000000000 + + + + + + + Max + + + + + + + QAbstractSpinBox::CorrectToNearestValue + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.010000000000000 + + + 1.000000000000000 + + + + + + + Step + + + + + + + QAbstractSpinBox::CorrectToNearestValue + + + 50.000000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + +
- - - - 0 - 0 - 91 - 271 - - - - - - 0 - 0 - 87 - 171 - - - - - 8 - - - - Qt::ScrollBarAlwaysOff - - - Qt::ScrollBarAlwaysOff - - - false - - - true - - - 5 - - - 1 - - - - 5 - - - - - 4 - - - - - 3 - - - - - 2 - - - - - 1 - - - - - Value - - - - - 1.0 - - - - - .75 - - - - - .50 - - - - - .25 - - - - - .00 - - - - - - - 0 - 180 - 87 - 20 - - - - - Linear - - - - - Log - - - - - Exp - - - - - Flat - - - - - Step - - - - - - - 0 - 200 - 87 - 23 - - - - Generate - - - - - - 0 - 240 - 87 - 23 - - - - Reset - - - - - - - 100 - 230 - 61 - 16 - - - - Min - - - - - - 100 - 250 - 61 - 20 - - - - QAbstractSpinBox::CorrectToNearestValue - - - -1.000000000000000 - - - 1.000000000000000 - - - 0.010000000000000 - - - 0.000000000000000 - - - - - - 240 - 230 - 87 - 13 - - - - Step - - - - - - 240 - 250 - 61 - 20 - - - - QAbstractSpinBox::CorrectToNearestValue - - - 50.000000000000000 - - - - - - 170 - 230 - 51 - 16 - - - - Max - - - - - - 170 - 250 - 61 - 20 - - - - QAbstractSpinBox::CorrectToNearestValue - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.010000000000000 - - - 1.000000000000000 - - - groupBox - verticalGroupBox - minLabel - CurveMin - stepLabel - CurveStep - maxLabel - CurveMax diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp index 5996eb7d3..199a0dba5 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp @@ -59,9 +59,7 @@ QList Node::edges() const QRectF Node::boundingRect() const { - qreal adjust = 2; - return QRectF(-12 - adjust, -12 - adjust, - 28 + adjust, 28 + adjust); + return QRectF(-12, -12, 25, 25); } QPainterPath Node::shape() const From 8692855208c581cc15f3dd9af703c35db604251d Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Thu, 5 Jul 2012 15:31:36 -0700 Subject: [PATCH 007/543] Bugfixes: spindelegate is online and fairly smart, knows min/max for curve; heli config is fully on board with integrated curve; custom vehicle now displays 10 channels in custom grid; mixercurve ui getting better; --- .../src/plugins/config/DoubleSpinDelegate.cpp | 21 ++++++--- .../src/plugins/config/DoubleSpinDelegate.h | 17 +++++++ .../cfg_vehicletypes/configccpmwidget.cpp | 22 ++++++++-- .../config/configvehicletypewidget.cpp | 8 ++-- .../src/plugins/config/mixercurve.cpp | 44 +++++++++++++++---- .../src/plugins/config/mixercurve.ui | 5 +-- 6 files changed, 91 insertions(+), 26 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.cpp b/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.cpp index dd5921431..d87cdfd70 100644 --- a/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.cpp +++ b/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.cpp @@ -31,15 +31,14 @@ Helper delegate for the custom mixer editor table. */ DoubleSpinDelegate::DoubleSpinDelegate(QObject *parent) - : QItemDelegate(parent), - m_min(0.0), - m_max(1.0), - m_decimals(2), - m_step(0.01) - { + : QItemDelegate(parent) + { + m_min = 0.0; + m_max = 1.0; + m_decimals = 2; + m_step = 0.01; } - QWidget *DoubleSpinDelegate::createEditor(QWidget *parent, const QStyleOptionViewItem &/* option */, const QModelIndex &/* index */) const @@ -49,6 +48,9 @@ QWidget *DoubleSpinDelegate::createEditor(QWidget *parent, editor->setMaximum(m_max); editor->setDecimals(m_decimals); editor->setSingleStep(m_step); + + connect(editor,SIGNAL(valueChanged(double)), this, SLOT(valueChanged())); + return editor; } @@ -77,3 +79,8 @@ void DoubleSpinDelegate::updateEditorGeometry(QWidget *editor, editor->setGeometry(option.rect); } +void DoubleSpinDelegate::valueChanged() +{ + emit ValueChanged(); +} + diff --git a/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.h b/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.h index 8329abb75..0711cf81d 100644 --- a/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.h +++ b/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.h @@ -30,6 +30,11 @@ #include #include + +namespace Ui { +class DoubleSpinDelegate; +} + class DoubleSpinDelegate : public QItemDelegate { Q_OBJECT @@ -47,11 +52,23 @@ public: void updateEditorGeometry(QWidget *editor, const QStyleOptionViewItem &option, const QModelIndex &index) const; + void setMin(double min) { m_min = min; } + void setMax(double max) { m_max = max; } + void setRange(double min, double max) { m_min = min; m_max = max; } + void setStep(double step) { m_step = step; } + void setDecimals(int decimals) { m_decimals = decimals; } + private: double m_min; double m_max; double m_step; int m_decimals; + +signals: + void ValueChanged(); + +private slots: + void valueChanged() ; }; #endif // DOUBLESPINDELEGATE_H diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp index 86879ec38..0cfbcb207 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp @@ -135,10 +135,10 @@ ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) : VehicleConfig(parent) //initialize our two mixer curves m_ccpm->ThrottleCurve->setMixerType(MixerCurve::MIXERCURVE_THROTTLE); - m_ccpm->ThrottleCurve->initLinearCurve(5, 1.0); + m_ccpm->ThrottleCurve->ResetCurve(); m_ccpm->PitchCurve->setMixerType(MixerCurve::MIXERCURVE_PITCH); - m_ccpm->PitchCurve->initLinearCurve(5, 1.0, -1.0); + m_ccpm->PitchCurve->ResetCurve(); //initialize channel names m_ccpm->ccpmEngineChannel->addItems(channelNames); @@ -840,10 +840,24 @@ void ConfigCcpmWidget::getMixer() QList curveValues; vconfig->getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, &curveValues); - m_ccpm->ThrottleCurve->setCurve(&curveValues); + + // is at least one of the curve values != 0? + if (vconfig->isValidThrottleCurve(&curveValues)) { + m_ccpm->ThrottleCurve->setCurve(&curveValues); + } + else { + m_ccpm->ThrottleCurve->ResetCurve(); + } + vconfig->getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, &curveValues); - m_ccpm->PitchCurve->setCurve(&curveValues); + // is at least one of the curve values != 0? + if (vconfig->isValidThrottleCurve(&curveValues)) { + m_ccpm->PitchCurve->setCurve(&curveValues); + } + else { + m_ccpm->PitchCurve->ResetCurve(); + } updatingFromHardware=FALSE; diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index c356bd0b3..5082daf22 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -325,7 +325,7 @@ void ConfigVehicleTypeWidget::switchAirframeType(int index) m_aircraft->customMixerTable->resizeColumnsToContents(); for (int i=0;i<(int)(VehicleConfig::CHANNEL_NUMELEM);i++) { m_aircraft->customMixerTable->setColumnWidth(i,(m_aircraft->customMixerTable->width()- - m_aircraft->customMixerTable->verticalHeader()->width())/8); + m_aircraft->customMixerTable->verticalHeader()->width())/10); } } } @@ -344,7 +344,7 @@ void ConfigVehicleTypeWidget::showEvent(QShowEvent *event) m_aircraft->customMixerTable->resizeColumnsToContents(); for (int i=0;i<(int)(VehicleConfig::CHANNEL_NUMELEM);i++) { m_aircraft->customMixerTable->setColumnWidth(i,(m_aircraft->customMixerTable->width()- - m_aircraft->customMixerTable->verticalHeader()->width())/8); + m_aircraft->customMixerTable->verticalHeader()->width())/ 10); } } @@ -357,9 +357,9 @@ void ConfigVehicleTypeWidget::resizeEvent(QResizeEvent* event) m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio); // Make the custom table columns autostretch: m_aircraft->customMixerTable->resizeColumnsToContents(); - for (int i=0;i<8;i++) { + for (int i=0;i<(int)(VehicleConfig::CHANNEL_NUMELEM);i++) { m_aircraft->customMixerTable->setColumnWidth(i,(m_aircraft->customMixerTable->width()- - m_aircraft->customMixerTable->verticalHeader()->width())/8); + m_aircraft->customMixerTable->verticalHeader()->width())/ 10); } } diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 76dd6da23..9171c8080 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -31,18 +31,14 @@ MixerCurve::MixerCurve(QWidget *parent) : QFrame(parent), - m_mixerUI(new Ui::MixerCurve), - m_curveType(MixerCurve::MIXERCURVE_THROTTLE) + m_mixerUI(new Ui::MixerCurve) { m_mixerUI->setupUi(this); m_curve = m_mixerUI->CurveWidget; m_settings = m_mixerUI->CurveSettings; - DoubleSpinDelegate *sbd = new DoubleSpinDelegate(); - for (int i=0; isetItemDelegateForRow(i, sbd); - } + setMixerType(MixerCurve::MIXERCURVE_THROTTLE); UpdateCurveUI(); @@ -50,7 +46,7 @@ MixerCurve::MixerCurve(QWidget *parent) : connect(m_mixerUI->ResetCurve, SIGNAL(clicked()), this, SLOT(ResetCurve())); connect(m_mixerUI->GenerateCurve, SIGNAL(clicked()), this, SLOT(GenerateCurve())); connect(m_curve, SIGNAL(curveUpdated()), this, SLOT(UpdateSettingsTable())); - connect(m_settings, SIGNAL(itemChanged(QTableWidgetItem*)), this, SLOT(SettingsTableChanged())); + connect(m_settings, SIGNAL(cellChanged(int,int)), this, SLOT(SettingsTableChanged())); connect(m_mixerUI->CurveMin, SIGNAL(valueChanged(double)), this, SLOT(CurveMinChanged(double))); connect(m_mixerUI->CurveMax, SIGNAL(valueChanged(double)), this, SLOT(CurveMaxChanged(double))); connect(m_mixerUI->CurveStep, SIGNAL(valueChanged(double)), this, SLOT(GenerateCurve())); @@ -64,7 +60,33 @@ MixerCurve::~MixerCurve() void MixerCurve::setMixerType(MixerCurveType curveType) { m_curveType = curveType; - m_mixerUI->CurveGroup->setTitle( (m_curveType == MixerCurve::MIXERCURVE_THROTTLE) ? "Throttle Curve" : "Pitch Curve"); + + switch (m_curveType) { + case MixerCurve::MIXERCURVE_THROTTLE: + { + m_mixerUI->CurveGroup->setTitle("Throttle Curve"); + m_curve->setRange(0.0, 1.0); + m_mixerUI->CurveMin->setMinimum(0.0); + m_mixerUI->CurveMax->setMinimum(0.0); + break; + } + case MixerCurve::MIXERCURVE_PITCH: + { + m_mixerUI->CurveGroup->setTitle("Pitch Curve"); + m_curve->setRange(-1.0, 1.0); + m_mixerUI->CurveMin->setMinimum(-1.0); + m_mixerUI->CurveMax->setMinimum(-1.0); + break; + } + } + + DoubleSpinDelegate *sbd = new DoubleSpinDelegate(); + sbd->setRange(m_curve->getMin(), m_curve->getMax()); + for (int i=0; isetItemDelegateForRow(i, sbd); + } + + ResetCurve(); } void MixerCurve::ResetCurve() @@ -328,6 +350,9 @@ void MixerCurve::showEvent(QShowEvent *event) { Q_UNUSED(event); + m_settings->resizeColumnsToContents(); + m_settings->setColumnWidth(0,(m_settings->width()- m_settings->verticalHeader()->width())); + m_curve->showEvent(event); } @@ -335,5 +360,8 @@ void MixerCurve::resizeEvent(QResizeEvent* event) { Q_UNUSED(event); + m_settings->resizeColumnsToContents(); + m_settings->setColumnWidth(0,(m_settings->width()- m_settings->verticalHeader()->width())); + m_curve->resizeEvent(event); } diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.ui b/ground/openpilotgcs/src/plugins/config/mixercurve.ui index e174a333f..7844ead2c 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.ui +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.ui @@ -62,7 +62,7 @@ - 100 + 150 16777215 @@ -74,7 +74,7 @@ - 71 + 100 200 @@ -281,7 +281,6 @@ 7 - CurveGroup From eeb9ce9909974a17f83593b503223bcb13a44d23 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 6 Jul 2012 10:43:24 -0700 Subject: [PATCH 008/543] Bugfix: resolve curveUpdated() signal signature issue. --- .../src/plugins/uavobjectwidgetutils/configtaskwidget.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 7fb8d70c7..41ddf9f05 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -843,7 +843,7 @@ void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget * widget,const char* f } else if(MixerCurveWidget * cb=qobject_cast(widget)) { - connect(cb,SIGNAL(curveUpdated(QList,double)),this,function); + connect(cb,SIGNAL(curveUpdated()),this,function); } else if(QTableWidget * cb=qobject_cast(widget)) { @@ -886,7 +886,7 @@ void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget * widget,const char } else if(MixerCurveWidget * cb=qobject_cast(widget)) { - disconnect(cb,SIGNAL(curveUpdated(QList,double)),this,function); + disconnect(cb,SIGNAL(curveUpdated()),this,function); } else if(QTableWidget * cb=qobject_cast(widget)) { From de590dfdd7981166a7641d0463833928bdf966cb Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 6 Jul 2012 11:28:46 -0700 Subject: [PATCH 009/543] MixerCurve: Bwahaha, it resizes. --- .../src/plugins/config/airframe.ui | 42 +- .../src/plugins/config/mixercurve.cpp | 16 +- .../src/plugins/config/mixercurve.ui | 680 +++++++++--------- .../uavobjectwidgetutils/mixercurvewidget.cpp | 1 + .../uavobjectwidgetutils/mixercurvewidget.h | 1 - 5 files changed, 385 insertions(+), 355 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 7ca5b937b..82097b90b 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -480,8 +480,8 @@ margin:1px; - 450 - 400 + 0 + 0 @@ -499,7 +499,7 @@ margin:1px; 300 - 300 + 350 @@ -876,6 +876,18 @@ margin:1px; 0 + + + 10 + 10 + + + + + 300 + 350 + + background:transparent @@ -1627,7 +1639,7 @@ margin:1px; - + 0 100 @@ -1662,6 +1674,12 @@ margin:1px; 10 + + + 300 + 350 + + @@ -1670,7 +1688,7 @@ margin:1px; - + 0 0 @@ -1699,6 +1717,18 @@ margin:1px; 500 + + + 10 + 10 + + + + + 300 + 350 + + @@ -1762,7 +1792,7 @@ margin:1px; - + 0 0 diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 9171c8080..9fe0ede74 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -25,6 +25,8 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include +#include #include #include "mixercurve.h" #include "doublespindelegate.h" @@ -64,7 +66,7 @@ void MixerCurve::setMixerType(MixerCurveType curveType) switch (m_curveType) { case MixerCurve::MIXERCURVE_THROTTLE: { - m_mixerUI->CurveGroup->setTitle("Throttle Curve"); + m_mixerUI->SettingsGroup->setTitle("Throttle Curve"); m_curve->setRange(0.0, 1.0); m_mixerUI->CurveMin->setMinimum(0.0); m_mixerUI->CurveMax->setMinimum(0.0); @@ -72,7 +74,7 @@ void MixerCurve::setMixerType(MixerCurveType curveType) } case MixerCurve::MIXERCURVE_PITCH: { - m_mixerUI->CurveGroup->setTitle("Pitch Curve"); + m_mixerUI->SettingsGroup->setTitle("Pitch Curve"); m_curve->setRange(-1.0, 1.0); m_mixerUI->CurveMin->setMinimum(-1.0); m_mixerUI->CurveMax->setMinimum(-1.0); @@ -353,15 +355,19 @@ void MixerCurve::showEvent(QShowEvent *event) m_settings->resizeColumnsToContents(); m_settings->setColumnWidth(0,(m_settings->width()- m_settings->verticalHeader()->width())); +// const QRectF& rectRef = QRectF(0,0,parentWidget()->width() - 50 , parentWidget()->width() - 50); +// m_curve->fitInView(rectRef, Qt::KeepAspectRatio); + m_curve->showEvent(event); } void MixerCurve::resizeEvent(QResizeEvent* event) { - Q_UNUSED(event); - m_settings->resizeColumnsToContents(); - m_settings->setColumnWidth(0,(m_settings->width()- m_settings->verticalHeader()->width())); + m_settings->setColumnWidth(0,(m_settings->width() - m_settings->verticalHeader()->width())); + +// const QRectF& rectRef = QRectF(0,0,parentWidget()->width() - 50 , parentWidget()->width() - 50); +// m_curve->fitInView(rectRef, Qt::KeepAspectRatio); m_curve->resizeEvent(event); } diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.ui b/ground/openpilotgcs/src/plugins/config/mixercurve.ui index 7844ead2c..ad6e8b696 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.ui +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.ui @@ -6,7 +6,7 @@ 0 0 - 447 + 441 321 @@ -18,8 +18,8 @@ - 200 - 200 + 441 + 321 @@ -43,348 +43,342 @@ QFrame::Raised - - - - 10 - 10 - 422 - 301 - - - - - - - QLayout::SetDefaultConstraint - - - - - - 150 - 16777215 - - - - Throttle Curve - - - - - - - 100 - 200 - - - - - 8 - - - - Qt::ScrollBarAlwaysOff - - - Qt::ScrollBarAlwaysOff - - - false - - - true - - - 5 - - - 1 - - - - 5 - - - - - 4 - - - - - 3 - - - - - 2 - - - - - 1 - - - - - Value - - - AlignJustify|AlignVCenter - - - - - 1.0 - - - - - .75 - - - - - .50 - - - - - .25 - - - - - .00 - - - - - - - - - Linear - - - - - Log - - - - - Exp - - - - - Flat - - - - - Step - - - - - - - - Generate - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - Reset - - - - - GenerateCurve - CurveSettings - ResetCurve - CurveType - verticalSpacer - - - - - - - - QLayout::SetDefaultConstraint - - - - - - 1 - 1 - - - - - QLayout::SetMinAndMaxSize + + + + + + + QLayout::SetDefaultConstraint + + + + + + 150 + 16777215 + - - - - - 5 - 5 - - - - - 50 - 50 - - - - - 1000 - 1000 - - - - - 10 - 10 - - - - - 200 - 200 - - - - - 7 - - - - - - - - - - + + Throttle Curve + + + + + + + 100 + 200 + + + + + 8 + + + + Qt::ScrollBarAlwaysOff + + + Qt::ScrollBarAlwaysOff + + + false + + + true + + + 5 + + + 1 + + + + 5 - - - - - Min - - - - - - - QAbstractSpinBox::CorrectToNearestValue - - - -1.000000000000000 - - - 1.000000000000000 - - - 0.010000000000000 - - - 0.000000000000000 - - - - - - - Max - - - - - - - QAbstractSpinBox::CorrectToNearestValue - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.010000000000000 - - - 1.000000000000000 - - - - - - - Step - - - - - - - QAbstractSpinBox::CorrectToNearestValue - - - 50.000000000000000 - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - - - - - + + + + 4 + + + + + 3 + + + + + 2 + + + + + 1 + + + + + Value + + + AlignJustify|AlignVCenter + + + + + 1.0 + + + + + .75 + + + + + .50 + + + + + .25 + + + + + .00 + + + + + + + + + Linear + + + + + Log + + + + + Exp + + + + + Flat + + + + + Step + + + + + + + + Generate + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + Reset + + + + + GenerateCurve + CurveSettings + ResetCurve + CurveType + verticalSpacer + + + + + + + + QLayout::SetDefaultConstraint + + + + + + 1 + 1 + + + + + QLayout::SetMinAndMaxSize + + + + + + 5 + 5 + + + + + 50 + 50 + + + + + 1000 + 1000 + + + + + 10 + 10 + + + + + 200 + 200 + + + + + 7 + + + + + + + + + + + + + + + + Min + + + + + + + QAbstractSpinBox::CorrectToNearestValue + + + -1.000000000000000 + + + 1.000000000000000 + + + 0.010000000000000 + + + 0.000000000000000 + + + + + + + Max + + + + + + + QAbstractSpinBox::CorrectToNearestValue + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.010000000000000 + + + 1.000000000000000 + + + + + + + Step + + + + + + + QAbstractSpinBox::CorrectToNearestValue + + + 50.000000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index eea8fef7b..65bc8bd4b 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -243,6 +243,7 @@ void MixerCurveWidget::showEvent(QShowEvent *event) void MixerCurveWidget::resizeEvent(QResizeEvent* event) { Q_UNUSED(event); + fitInView(plot, Qt::KeepAspectRatio); } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h index 338974f28..dcf9dc93a 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h @@ -72,7 +72,6 @@ private: QList nodePool; QList edgePool; QList nodeList; - QList points; double curveMin; double curveMax; From 06eb23abe61fd28a9dd99cdf6520b29520700ecb Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 6 Jul 2012 11:44:16 -0700 Subject: [PATCH 010/543] MixerCurve, bugfix: min and max nodes no longer clipped. --- .../src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index 65bc8bd4b..ca5c5cf84 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -236,15 +236,19 @@ void MixerCurveWidget::showEvent(QShowEvent *event) // Thit fitInView method should only be called now, once the // widget is shown, otherwise it cannot compute its values and // the result is usually a ahrsbargraph that is way too small. - fitInView(plot, Qt::KeepAspectRatio); + QRectF rect = plot->boundingRect(); + + fitInView(rect.adjusted(-12,-12,12,12), Qt::KeepAspectRatio); } void MixerCurveWidget::resizeEvent(QResizeEvent* event) { Q_UNUSED(event); - fitInView(plot, Qt::KeepAspectRatio); + QRectF rect = plot->boundingRect(); + + fitInView(rect.adjusted(-12,-12,12,12), Qt::KeepAspectRatio); } void MixerCurveWidget::itemMoved(double itemValue) From 382fecabbe8286645b518c7d677655214cc2883c Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 6 Jul 2012 13:38:46 -0700 Subject: [PATCH 011/543] Bugfixes: distingish between curve base min/max and client requested (multi's & 90% max); keep spindelegate synched with requested min/max's; clean up a few old field based references; make all nodes move when curve is flat; --- .../configfixedwingwidget.cpp | 3 +- .../configgroundvehiclewidget.cpp | 21 ++---- .../src/plugins/config/mixercurve.cpp | 71 +++++++++---------- .../src/plugins/config/mixercurve.h | 2 + .../uavobjectwidgetutils/mixercurvewidget.cpp | 2 +- 5 files changed, 45 insertions(+), 54 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 727a2f52d..ecc933eec 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -186,8 +186,7 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() Q_ASSERT(mixer); // Remove Feed Forward, it is pointless on a plane: - UAVObjectField* field = mixer->getField(QString("FeedForward")); - field->setDouble(0); + setMixerValue(mixer, "FeedForward", 0.0); // Set the throttle curve setThrottleCurve(mixer,VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->fixedWingThrottle->getCurve()); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp index 8f2946d78..a5df943c8 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.cpp @@ -198,24 +198,15 @@ QString ConfigGroundVehicleWidget::updateConfigObjectsFromWidgets() QString airframeType = "GroundVehicleCar"; // Save the curve (common to all ground vehicle frames) - UAVDataObject *obj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); // Remove Feed Forward, it is pointless on a ground vehicle: - UAVObjectField* field = obj->getField(QString("FeedForward")); - field->setDouble(0); - - field = obj->getField("ThrottleCurve1"); - QList curve = m_aircraft->groundVehicleThrottle1->getCurve(); - for (int i=0;isetValue(curve.at(i),i); - } + setMixerValue(mixer, "FeedForward", 0.0); + + // set the throttle curves + setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->groundVehicleThrottle1->getCurve() ); + setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, m_aircraft->groundVehicleThrottle2->getCurve() ); - field = obj->getField("ThrottleCurve2"); - curve = m_aircraft->groundVehicleThrottle2->getCurve(); - for (int i=0;isetValue(curve.at(i),i); - } - //All airframe types must start with "GroundVehicle" if (m_aircraft->groundVehicleType->currentText() == "Turnable (car)" ) { airframeType = "GroundVehicleCar"; diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 9fe0ede74..6d6f6943e 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -57,12 +57,16 @@ MixerCurve::MixerCurve(QWidget *parent) : MixerCurve::~MixerCurve() { delete m_mixerUI; + delete m_spinDelegate; } void MixerCurve::setMixerType(MixerCurveType curveType) { m_curveType = curveType; + m_mixerUI->CurveMin->setMaximum(1.0); + m_mixerUI->CurveMax->setMaximum(1.0); + switch (m_curveType) { case MixerCurve::MIXERCURVE_THROTTLE: { @@ -82,10 +86,10 @@ void MixerCurve::setMixerType(MixerCurveType curveType) } } - DoubleSpinDelegate *sbd = new DoubleSpinDelegate(); - sbd->setRange(m_curve->getMin(), m_curve->getMax()); + m_spinDelegate = new DoubleSpinDelegate(); + m_spinDelegate->setRange(m_mixerUI->CurveMin->minimum(), m_mixerUI->CurveMax->maximum()); for (int i=0; isetItemDelegateForRow(i, sbd); + m_settings->setItemDelegateForRow(i, m_spinDelegate); } ResetCurve(); @@ -93,11 +97,11 @@ void MixerCurve::setMixerType(MixerCurveType curveType) void MixerCurve::ResetCurve() { - m_mixerUI->CurveMin->setValue(m_curve->getMin()); - m_mixerUI->CurveMax->setValue(m_curve->getMax()); + m_mixerUI->CurveMin->setValue(m_mixerUI->CurveMin->minimum()); + m_mixerUI->CurveMax->setValue(m_mixerUI->CurveMax->maximum()); m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Linear")); - initLinearCurve(MixerCurveWidget::NODE_NUMELEM, m_curve->getMax(), m_curve->getMin()); + initLinearCurve(MixerCurveWidget::NODE_NUMELEM, getCurveMax(), getCurveMin()); UpdateSettingsTable(); } @@ -107,23 +111,6 @@ void MixerCurve::UpdateCurveUI() //get the user settings QString curveType = m_mixerUI->CurveType->currentText(); - switch (m_curveType) { - case MixerCurve::MIXERCURVE_THROTTLE: - { - m_mixerUI->CurveMin->setMinimum(0.0); - m_mixerUI->CurveMax->setMinimum(0.0); - break; - } - case MixerCurve::MIXERCURVE_PITCH: - { - m_mixerUI->CurveMin->setMinimum(-1.0); - m_mixerUI->CurveMax->setMinimum(-1.0); - break; - } - } - m_mixerUI->CurveMin->setMaximum(m_curve->getMax()); - m_mixerUI->CurveMax->setMaximum(m_curve->getMax()); - m_mixerUI->CurveStep->setMinimum(0.0); m_mixerUI->CurveStep->setMaximum(100.0); @@ -151,7 +138,8 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->CurveMax->setVisible(true); m_mixerUI->stepLabel->setText("Step at"); m_mixerUI->stepLabel->setVisible(true); - m_mixerUI->CurveStep->setVisible(true); + m_mixerUI->CurveStep->setVisible(true); + m_mixerUI->CurveStep->setMaximum(4.0); } if ( curveType.compare("Exp")==0) { @@ -247,6 +235,9 @@ void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue setMax(maxValue); m_curve->initLinearCurve(numPoints, maxValue, minValue); + + if (m_spinDelegate) + m_spinDelegate->setRange(minValue, maxValue); } void MixerCurve::setCurve(const QList* points) { @@ -255,7 +246,7 @@ void MixerCurve::setCurve(const QList* points) } void MixerCurve::setMin(double value) { - m_curve->setMin(value); + //m_curve->setMin(value); m_mixerUI->CurveMin->setMinimum(value); } double MixerCurve::getMin() @@ -264,7 +255,7 @@ double MixerCurve::getMin() } void MixerCurve::setMax(double value) { - m_curve->setMax(value); + //m_curve->setMax(value); m_mixerUI->CurveMax->setMaximum(value); } double MixerCurve::getMax() @@ -330,11 +321,25 @@ void MixerCurve::CurveTypeChanged() void MixerCurve::CurveMinChanged(double value) { - // the min changed so redraw the curve - // mixercurvewidget::setCurve will trim any points below min QList points = m_curve->getCurve(); - points.removeFirst(); - points.push_front(value); + QString CurveType = m_mixerUI->CurveType->currentText(); + + if ( CurveType.compare("Flat")==0) { + // the min changed so redraw the curve + // but since the curve is flat make all points = value + // because we use curveMin for the flat value in ui + for (int i = 0; i < points.count(); i++) { + points.pop_back(); + points.push_front(value); + } + } + else { + // the min changed so redraw the curve + // mixercurvewidget::setCurve will trim any points below min + + points.removeFirst(); + points.push_front(value); + } setCurve(&points); } @@ -355,9 +360,6 @@ void MixerCurve::showEvent(QShowEvent *event) m_settings->resizeColumnsToContents(); m_settings->setColumnWidth(0,(m_settings->width()- m_settings->verticalHeader()->width())); -// const QRectF& rectRef = QRectF(0,0,parentWidget()->width() - 50 , parentWidget()->width() - 50); -// m_curve->fitInView(rectRef, Qt::KeepAspectRatio); - m_curve->showEvent(event); } @@ -366,8 +368,5 @@ void MixerCurve::resizeEvent(QResizeEvent* event) m_settings->resizeColumnsToContents(); m_settings->setColumnWidth(0,(m_settings->width() - m_settings->verticalHeader()->width())); -// const QRectF& rectRef = QRectF(0,0,parentWidget()->width() - 50 , parentWidget()->width() - 50); -// m_curve->fitInView(rectRef, Qt::KeepAspectRatio); - m_curve->resizeEvent(event); } diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.h b/ground/openpilotgcs/src/plugins/config/mixercurve.h index 3133da660..5324aebad 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.h +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.h @@ -34,6 +34,7 @@ #include "ui_mixercurve.h" #include "mixercurvewidget.h" +#include "doublespindelegate.h" #include "uavobjectwidgetutils_global.h" @@ -91,6 +92,7 @@ private: MixerCurveWidget* m_curve; QTableWidget* m_settings; MixerCurveType m_curveType; + DoubleSpinDelegate* m_spinDelegate; }; diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index ca5c5cf84..543d85151 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -185,7 +185,7 @@ QList MixerCurveWidget::getCurve() { */ void MixerCurveWidget::initLinearCurve(int numPoints, double maxValue, double minValue) { - double range = setRange(minValue, maxValue); + double range = maxValue - minValue; // setRange(minValue, maxValue); QList points; for (double i=0; i < (double)numPoints; i++) { From 51891881dbd60e0ff4e30b24f0098929076a03c2 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 6 Jul 2012 14:01:53 -0700 Subject: [PATCH 012/543] Tweeks: verify heli init's curves correctly; mixer pre-allocates a spindelegate so we can reset min/max later --- .../plugins/config/cfg_vehicletypes/configccpmwidget.cpp | 8 ++++---- ground/openpilotgcs/src/plugins/config/mixercurve.cpp | 8 +++++++- 2 files changed, 11 insertions(+), 5 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp index 0cfbcb207..7234ffbf4 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp @@ -133,12 +133,12 @@ ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) : VehicleConfig(parent) } //initialize our two mixer curves + // mixercurve defaults to mixercurve_throttle + m_ccpm->ThrottleCurve->initLinearCurve(5, 1.0, 0.0); - m_ccpm->ThrottleCurve->setMixerType(MixerCurve::MIXERCURVE_THROTTLE); - m_ccpm->ThrottleCurve->ResetCurve(); - + // tell mixercurve this is a pitch curve m_ccpm->PitchCurve->setMixerType(MixerCurve::MIXERCURVE_PITCH); - m_ccpm->PitchCurve->ResetCurve(); + m_ccpm->PitchCurve->initLinearCurve(5, 1.0, -1.0); //initialize channel names m_ccpm->ccpmEngineChannel->addItems(channelNames); diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 6d6f6943e..e9579cb67 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -37,13 +37,20 @@ MixerCurve::MixerCurve(QWidget *parent) : { m_mixerUI->setupUi(this); + // setup some convienence pointers m_curve = m_mixerUI->CurveWidget; m_settings = m_mixerUI->CurveSettings; + // create our spin delegate + m_spinDelegate = new DoubleSpinDelegate(); + + // set the default mixer type setMixerType(MixerCurve::MIXERCURVE_THROTTLE); + // paint the ui UpdateCurveUI(); + // wire up our signals connect(m_mixerUI->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(CurveTypeChanged())); connect(m_mixerUI->ResetCurve, SIGNAL(clicked()), this, SLOT(ResetCurve())); connect(m_mixerUI->GenerateCurve, SIGNAL(clicked()), this, SLOT(GenerateCurve())); @@ -86,7 +93,6 @@ void MixerCurve::setMixerType(MixerCurveType curveType) } } - m_spinDelegate = new DoubleSpinDelegate(); m_spinDelegate->setRange(m_mixerUI->CurveMin->minimum(), m_mixerUI->CurveMax->maximum()); for (int i=0; isetItemDelegateForRow(i, m_spinDelegate); From 44140931ae7e2682cd6eb6b463303d4ca897d2b1 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 6 Jul 2012 15:02:34 -0700 Subject: [PATCH 013/543] Tweek: resize the settings table row heights. --- ground/openpilotgcs/src/plugins/config/mixercurve.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index e9579cb67..0c1686d6b 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -366,6 +366,10 @@ void MixerCurve::showEvent(QShowEvent *event) m_settings->resizeColumnsToContents(); m_settings->setColumnWidth(0,(m_settings->width()- m_settings->verticalHeader()->width())); + int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount(); + for (int i=0; irowCount(); i++) + m_settings->setRowHeight(i, h); + m_curve->showEvent(event); } @@ -374,5 +378,9 @@ void MixerCurve::resizeEvent(QResizeEvent* event) m_settings->resizeColumnsToContents(); m_settings->setColumnWidth(0,(m_settings->width() - m_settings->verticalHeader()->width())); + int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount(); + for (int i=0; irowCount(); i++) + m_settings->setRowHeight(i, h); + m_curve->resizeEvent(event); } From dc4c6c74e415e09f6a552efb665c9f708555f3f6 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 6 Jul 2012 15:16:54 -0700 Subject: [PATCH 014/543] Tweek: set min/max spinboxes to match the settings table when edited. --- ground/openpilotgcs/src/plugins/config/mixercurve.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 0c1686d6b..382a20908 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -313,6 +313,9 @@ void MixerCurve::SettingsTableChanged() points.push_front(item->text().toDouble()); } + m_mixerUI->CurveMin->setValue(points.first()); + m_mixerUI->CurveMax->setValue(points.last()); + m_curve->setCurve(&points); } From 6a12701e639714d11baa0d8231723e6a19df225b Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 6 Jul 2012 16:12:53 -0700 Subject: [PATCH 015/543] Bugfix: wire up the mixercurvewidget to the dirty manager rather than the parent MixerCurve --- .../plugins/config/configvehicletypewidget.cpp | 16 ++++++++-------- .../openpilotgcs/src/plugins/config/mixercurve.h | 1 + 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 5082daf22..014efe411 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -777,13 +777,13 @@ void ConfigVehicleTypeWidget::setComboCurrentIndex(QComboBox* box, int index) void ConfigVehicleTypeWidget::addToDirtyMonitor() { addWidget(m_aircraft->customMixerTable); - addWidget(m_aircraft->customThrottle1Curve); - addWidget(m_aircraft->customThrottle2Curve); - addWidget(m_aircraft->multiThrottleCurve); - addWidget(m_aircraft->fixedWingThrottle); + addWidget(m_aircraft->customThrottle1Curve->getCurveWidget()); + addWidget(m_aircraft->customThrottle2Curve->getCurveWidget()); + addWidget(m_aircraft->multiThrottleCurve->getCurveWidget()); + addWidget(m_aircraft->fixedWingThrottle->getCurveWidget()); addWidget(m_aircraft->fixedWingType); - addWidget(m_aircraft->groundVehicleThrottle1); - addWidget(m_aircraft->groundVehicleThrottle2); + addWidget(m_aircraft->groundVehicleThrottle1->getCurveWidget()); + addWidget(m_aircraft->groundVehicleThrottle2->getCurveWidget()); addWidget(m_aircraft->groundVehicleType); addWidget(m_aircraft->feedForwardSlider); addWidget(m_aircraft->accelTime); @@ -841,8 +841,8 @@ void ConfigVehicleTypeWidget::addToDirtyMonitor() addWidget(m_heli->m_ccpm->ccpmRollScaleBox); addWidget(m_heli->m_ccpm->SwashLvlPositionSlider); addWidget(m_heli->m_ccpm->SwashLvlPositionSpinBox); - addWidget(m_heli->m_ccpm->ThrottleCurve); - addWidget(m_heli->m_ccpm->PitchCurve); + addWidget(m_heli->m_ccpm->ThrottleCurve->getCurveWidget()); + addWidget(m_heli->m_ccpm->PitchCurve->getCurveWidget()); addWidget(m_heli->m_ccpm->ccpmAdvancedSettingsTable); } diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.h b/ground/openpilotgcs/src/plugins/config/mixercurve.h index 5324aebad..1cda78284 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.h +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.h @@ -68,6 +68,7 @@ public: double getCurveStep(); double setRange(double min, double max); + MixerCurveWidget* getCurveWidget() { return m_curve; } signals: From b95290a32f8d0ebbcfc4e11b9c8fa4bb7e30cfe4 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 6 Jul 2012 21:47:08 -0700 Subject: [PATCH 016/543] Bugfix: reset min/max ui spinboxes on curvetype change. --- ground/openpilotgcs/src/plugins/config/mixercurve.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 382a20908..bacc01e98 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -117,6 +117,9 @@ void MixerCurve::UpdateCurveUI() //get the user settings QString curveType = m_mixerUI->CurveType->currentText(); + m_mixerUI->CurveMin->setValue(m_mixerUI->CurveMin->minimum()); + m_mixerUI->CurveMax->setValue(m_mixerUI->CurveMax->maximum()); + m_mixerUI->CurveStep->setMinimum(0.0); m_mixerUI->CurveStep->setMaximum(100.0); @@ -323,9 +326,6 @@ void MixerCurve::CurveTypeChanged() { // setup the ui for this curvetype UpdateCurveUI(); - - // and generate a curve based on the selection - GenerateCurve(); } void MixerCurve::CurveMinChanged(double value) From 115f9ba47392fcfac6110406688cc92ab8b89e3b Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sat, 7 Jul 2012 12:57:11 +0200 Subject: [PATCH 017/543] OP-359 Added setting in UAVO browser widget to enable/disable editors using scientific notation. --- .../plugins/uavobjectbrowser/fieldtreeitem.h | 62 +++++++++++-------- .../src/plugins/uavobjectbrowser/treeitem.h | 3 +- .../uavobjectbrowser/uavobjectbrowser.ui | 10 +++ .../uavobjectbrowserwidget.cpp | 15 +++++ .../uavobjectbrowser/uavobjectbrowserwidget.h | 1 + .../uavobjectbrowser/uavobjecttreemodel.cpp | 5 +- .../uavobjectbrowser/uavobjecttreemodel.h | 3 +- 7 files changed, 67 insertions(+), 32 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/fieldtreeitem.h b/ground/openpilotgcs/src/plugins/uavobjectbrowser/fieldtreeitem.h index 366121d00..bd980749f 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/fieldtreeitem.h +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/fieldtreeitem.h @@ -48,8 +48,6 @@ #define QINT32MAX std::numeric_limits::max() #define QUINT32MAX std::numeric_limits::max() -//#define USE_SCIENTIFIC_NOTATION - class FieldTreeItem : public TreeItem { Q_OBJECT @@ -214,10 +212,10 @@ class FloatFieldTreeItem : public FieldTreeItem { Q_OBJECT public: - FloatFieldTreeItem(UAVObjectField *field, int index, const QList &data, TreeItem *parent = 0) : - FieldTreeItem(index, data, parent), m_field(field) { } - FloatFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, TreeItem *parent = 0) : - FieldTreeItem(index, data, parent), m_field(field) { } + FloatFieldTreeItem(UAVObjectField *field, int index, const QList &data, bool scientific = false, TreeItem *parent = 0) : + FieldTreeItem(index, data, parent), m_field(field), m_useScientificNotation(scientific){} + FloatFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, bool scientific = false, TreeItem *parent = 0) : + FieldTreeItem(index, data, parent), m_field(field), m_useScientificNotation(scientific) { } void setData(QVariant value, int column) { setChanged(m_field->getValue(m_index) != value); TreeItem::setData(value, column); @@ -233,39 +231,49 @@ public: setHighlight(true); } } + QWidget *createEditor(QWidget *parent) { - #ifdef USE_SCIENTIFIC_NOTATION - QScienceSpinBox *editor = new QScienceSpinBox(parent); - editor->setDecimals(6); - #else + if(m_useScientificNotation) { + QScienceSpinBox *editor = new QScienceSpinBox(parent); + editor->setDecimals(6); + editor->setMinimum(-std::numeric_limits::max()); + editor->setMaximum(std::numeric_limits::max()); + return editor; + } else { QDoubleSpinBox *editor = new QDoubleSpinBox(parent); editor->setDecimals(8); - #endif - editor->setMinimum(-std::numeric_limits::max()); - editor->setMaximum(std::numeric_limits::max()); - return editor; + editor->setMinimum(-std::numeric_limits::max()); + editor->setMaximum(std::numeric_limits::max()); + return editor; + } } QVariant getEditorValue(QWidget *editor) { - #ifdef USE_SCIENTIFIC_NOTATION - QScienceSpinBox *spinBox = static_cast(editor); - #else - QDoubleSpinBox *spinBox = static_cast(editor); - #endif - spinBox->interpretText(); - return spinBox->value(); + if(m_useScientificNotation) { + QScienceSpinBox *spinBox = static_cast(editor); + spinBox->interpretText(); + return spinBox->value(); + } else { + QDoubleSpinBox *spinBox = static_cast(editor); + spinBox->interpretText(); + return spinBox->value(); + } } void setEditorValue(QWidget *editor, QVariant value) { - #ifdef USE_SCIENTIFIC_NOTATION - QScienceSpinBox *spinBox = static_cast(editor); - #else - QDoubleSpinBox *spinBox = static_cast(editor); - #endif - spinBox->setValue(value.toDouble()); + + if(m_useScientificNotation) { + QScienceSpinBox *spinBox = static_cast(editor); + spinBox->setValue(value.toDouble()); + } else { + QDoubleSpinBox *spinBox = static_cast(editor); + spinBox->setValue(value.toDouble()); + } } private: UAVObjectField *m_field; + bool m_useScientificNotation; + }; #endif // FIELDTREEITEM_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/treeitem.h b/ground/openpilotgcs/src/plugins/uavobjectbrowser/treeitem.h index 708513d91..90e6bfdf8 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/treeitem.h +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/treeitem.h @@ -146,10 +146,9 @@ private: bool m_changed; QTime m_highlightExpires; HighLightManager* m_highlightManager; + static int m_highlightTimeMs; public: static const int dataColumn = 1; -private: - static int m_highlightTimeMs; }; class TopTreeItem : public TreeItem diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui index 091c0c5eb..ba4807c34 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui @@ -202,6 +202,16 @@ + + + + Use scientific editors + + + Scientific + + + diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp index 31c395ccc..b7d0644dc 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp @@ -59,6 +59,7 @@ UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent connect(m_browser->eraseSDButton, SIGNAL(clicked()), this, SLOT(eraseObject())); connect(m_browser->sendButton, SIGNAL(clicked()), this, SLOT(sendUpdate())); connect(m_browser->requestButton, SIGNAL(clicked()), this, SLOT(requestUpdate())); + connect(m_browser->scientificNotationCheckbox, SIGNAL(toggled(bool)), this, SLOT(useScientificNotation(bool))); enableSendRequest(false); } @@ -79,6 +80,20 @@ void UAVObjectBrowserWidget::showMetaData(bool show) } } +void UAVObjectBrowserWidget::useScientificNotation(bool scientific) +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + Q_ASSERT(pm); + UAVObjectManager *objManager = pm->getObject(); + Q_ASSERT(objManager); + + UAVObjectTreeModel* tmpModel = m_model; + m_model = new UAVObjectTreeModel(0, scientific); + m_browser->treeView->setModel(m_model); + + delete tmpModel; +} + void UAVObjectBrowserWidget::sendUpdate() { ObjectTreeItem *objItem = findCurrentObjectTreeItem(); diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h index b047d37f0..cd058dadc 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h @@ -51,6 +51,7 @@ public: public slots: void showMetaData(bool show); + void useScientificNotation(bool scientific); private slots: void sendUpdate(); diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp index 120d9d0d8..6bc5a7925 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp @@ -38,8 +38,9 @@ #include #include -UAVObjectTreeModel::UAVObjectTreeModel(QObject *parent) : +UAVObjectTreeModel::UAVObjectTreeModel(QObject *parent, bool useScientificNotation) : QAbstractItemModel(parent), + m_useScientificFloatNotation(useScientificNotation), m_recentlyUpdatedTimeout(500), // ms m_recentlyUpdatedColor(QColor(255, 230, 230)), m_manuallyChangedColor(QColor(230, 230, 255)) @@ -198,7 +199,7 @@ void UAVObjectTreeModel::addSingleField(int index, UAVObjectField *field, TreeIt case UAVObjectField::FLOAT32: data.append(field->getValue(index)); data.append(field->getUnits()); - item = new FloatFieldTreeItem(field, index, data); + item = new FloatFieldTreeItem(field, index, data, m_useScientificFloatNotation); break; default: Q_ASSERT(false); diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h index d9787e3a7..fbb08dc28 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h @@ -48,7 +48,7 @@ class UAVObjectTreeModel : public QAbstractItemModel { Q_OBJECT public: - explicit UAVObjectTreeModel(QObject *parent = 0); + explicit UAVObjectTreeModel(QObject *parent = 0, bool useScientificNotation = false); ~UAVObjectTreeModel(); QVariant data(const QModelIndex &index, int role) const; @@ -97,6 +97,7 @@ private: int m_recentlyUpdatedTimeout; QColor m_recentlyUpdatedColor; QColor m_manuallyChangedColor; + bool m_useScientificFloatNotation; // Highlight manager to handle highlighting of tree items. HighLightManager *m_highlightManager; From c3057dc72e0818da7bc24e8358056099118c72d6 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sat, 7 Jul 2012 08:02:10 -0700 Subject: [PATCH 018/543] VehicleConfig Bugfix/tweek: change getChannelDescs to static in all airframes; avoids entire widget creation just to get channel descs. --- .../cfg_vehicletypes/configccpmwidget.h | 2 +- .../cfg_vehicletypes/configfixedwingwidget.h | 2 +- .../configgroundvehiclewidget.h | 2 +- .../cfg_vehicletypes/configmultirotorwidget.h | 2 +- .../config/cfg_vehicletypes/vehicleconfig.cpp | 11 -------- .../config/cfg_vehicletypes/vehicleconfig.h | 1 - .../config/configvehicletypewidget.cpp | 28 ++++--------------- .../plugins/config/configvehicletypewidget.h | 1 - 8 files changed, 10 insertions(+), 39 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h index 5e59a946f..a903afa5b 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h @@ -88,7 +88,7 @@ private: bool updatingToHardware; virtual void ResetActuators(GUIConfigDataUnion* configData); - virtual QStringList getChannelDescriptions(); + static QStringList getChannelDescriptions(); QString updateConfigObjects(); private slots: diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index 99eab5c06..7897829b3 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -57,7 +57,7 @@ private: bool setupFrameVtail(QString airframeType); virtual void ResetActuators(GUIConfigDataUnion* configData); - virtual QStringList getChannelDescriptions(); + static QStringList getChannelDescriptions(); private slots: virtual void setupUI(QString airframeType); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h index b2b447e6e..fb6cc48b2 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configgroundvehiclewidget.h @@ -57,7 +57,7 @@ private: bool setupGroundVehicleMotorcycle(QString airframeType); virtual void ResetActuators(GUIConfigDataUnion* configData); - virtual QStringList getChannelDescriptions(); + static QStringList getChannelDescriptions(); private slots: virtual void setupUI(QString airframeType); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h index 69b1e1712..cb8dfa8c9 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h @@ -65,7 +65,7 @@ private: void setupQuadMotor(int channel, double roll, double pitch, double yaw); virtual void ResetActuators(GUIConfigDataUnion* configData); - virtual QStringList getChannelDescriptions(); + static QStringList getChannelDescriptions(); private slots: virtual void setupUI(QString airframeType); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp index 94c3111b3..fc6fe4322 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp @@ -113,17 +113,6 @@ void VehicleConfig::SetConfigData(GUIConfigDataUnion configData) { void VehicleConfig::ResetActuators(GUIConfigDataUnion* configData) { } -QStringList VehicleConfig::getChannelDescriptions() -{ - QStringList channelDesc; - - // init a channel_numelem list of channel desc defaults - for (int i=0; i < (int)(VehicleConfig::CHANNEL_NUMELEM); i++) - { - channelDesc.append(QString("-")); - } - return channelDesc; -} /** Helper function: diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h index 31447f3f8..7ed9d986c 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h @@ -138,7 +138,6 @@ class VehicleConfig: public ConfigTaskWidget double getCurveMin(QList* curve); double getCurveMax(QList* curve); virtual void ResetActuators(GUIConfigDataUnion* configData); - virtual QStringList getChannelDescriptions(); QStringList channelNames; QStringList mixerTypes; diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 014efe411..a3bf8ee08 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -120,7 +120,7 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi airframeTypes << "Fixed Wing" << "Multirotor" << "Helicopter" << "Ground" << "Custom"; m_aircraft->aircraftType->addItems(airframeTypes); - m_aircraft->aircraftType->setCurrentIndex(0); //Set default vehicle to Fixed Wing + m_aircraft->aircraftType->setCurrentIndex(0); //Set default vehicle to Fixedwing m_aircraft->airframesWidget->setCurrentIndex(0); // Force the tab index to match QStringList fixedWingTypes; @@ -138,7 +138,7 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi "Hexacopter" << "Hexacopter X" << "Hexacopter Y6" << "Octocopter" << "Octocopter V" << "Octo Coax +" << "Octo Coax X" ; m_aircraft->multirotorFrameType->addItems(multiRotorTypes); - m_aircraft->multirotorFrameType->setCurrentIndex(1); //Set default model to "Quad +" + m_aircraft->multirotorFrameType->setCurrentIndex(2); //Set default model to "Quad X" //NEW STYLE: Loop through the widgets looking for all widgets that have "ChannelBox" in their name @@ -194,9 +194,6 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi m_heli = m_aircraft->widget_3; m_heli->setupUI(QString("HeliCP")); - // initialize the ui to show the mixersettings tab - //mdl m_aircraft->tabWidget->setCurrentIndex(0); - //Connect aircraft type selection dropbox to callback function connect(m_aircraft->aircraftType, SIGNAL(currentIndexChanged(int)), this, SLOT(switchAirframeType(int))); @@ -255,16 +252,14 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions() case SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON: case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL: { - QPointer fixedwing = new ConfigFixedWingWidget(); - channelDesc = fixedwing->getChannelDescriptions(); + channelDesc = ConfigFixedWingWidget::getChannelDescriptions(); } break; // helicp case SystemSettings::AIRFRAMETYPE_HELICP: { - QPointer heli = new ConfigCcpmWidget(); - channelDesc = heli->getChannelDescriptions(); + channelDesc = ConfigCcpmWidget::getChannelDescriptions(); } break; @@ -281,8 +276,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions() case SystemSettings::AIRFRAMETYPE_HEXACOAX: case SystemSettings::AIRFRAMETYPE_HEXA: { - QPointer multi = new ConfigMultiRotorWidget(); - channelDesc = multi->getChannelDescriptions(); + channelDesc = ConfigMultiRotorWidget::getChannelDescriptions(); } break; @@ -291,8 +285,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions() case SystemSettings::AIRFRAMETYPE_GROUNDVEHICLEDIFFERENTIAL: case SystemSettings::AIRFRAMETYPE_GROUNDVEHICLEMOTORCYCLE: { - QPointer ground = new ConfigGroundVehicleWidget(); - channelDesc = ground->getChannelDescriptions(); + channelDesc = ConfigGroundVehicleWidget::getChannelDescriptions(); } break; @@ -460,15 +453,6 @@ void ConfigVehicleTypeWidget::enableFFTest() } } -/** - Resets a mixer curve - */ -void ConfigVehicleTypeWidget::resetMixer(MixerCurveWidget *mixer, int numElements, double maxvalue) -{ - // Setup all Throttle1 curves for all types of airframes - mixer->initLinearCurve((quint32)numElements,maxvalue); -} - /************************** * Aircraft settings **************************/ diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h index 7eb9832e6..60ef74fbe 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h @@ -67,7 +67,6 @@ private: void updateCustomAirframeUI(); void addToDirtyMonitor(); void resetField(UAVObjectField * field); - void resetMixer (MixerCurveWidget *mixer, int numElements, double maxvalue); //void setMixerChannel(int channelNumber, bool channelIsMotor, QList vector); From 9c1f9d6b74be00fd4925e210ec5c8e6e32ddbb55 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sat, 7 Jul 2012 08:45:28 -0700 Subject: [PATCH 019/543] MixerCurve, Bugfix: make custom curve2 aware of throttle vs pitch curvetypes --- .../plugins/config/configvehicletypewidget.cpp | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index a3bf8ee08..fbad34e22 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -612,9 +612,6 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI() // is at least one of the curve values != 0? if (vconfig->isValidThrottleCurve(&curveValues)) { - // yes, use the curve we just read from mixersettings - m_aircraft->customThrottle1Curve->setMin(vconfig->getCurveMin(&curveValues)); - m_aircraft->customThrottle1Curve->setMax(vconfig->getCurveMax(&curveValues)); m_aircraft->customThrottle1Curve->initCurve(&curveValues); } else { @@ -622,12 +619,18 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI() m_aircraft->customThrottle1Curve->initLinearCurve(curveValues.count(),(double)1); } - // Setup all Throttle2 curves for all types of airframes //AT THIS MOMENT, THAT MEANS ONLY GROUND VEHICLES + if (MixerSettings* mxr = qobject_cast(mixer)) { + MixerSettings::DataFields mixerSettingsData = mxr->getData(); + if (mixerSettingsData.Curve2Source == MixerSettings::CURVE2SOURCE_THROTTLE) + m_aircraft->customThrottle2Curve->setMixerType(MixerCurve::MIXERCURVE_THROTTLE); + else + m_aircraft->customThrottle2Curve->setMixerType(MixerCurve::MIXERCURVE_PITCH); + } + + // Setup all Throttle2 curves for all types of airframes vconfig->getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, &curveValues); if (vconfig->isValidThrottleCurve(&curveValues)) { - m_aircraft->customThrottle2Curve->setMin(vconfig->getCurveMin(&curveValues)); - m_aircraft->customThrottle2Curve->setMax(vconfig->getCurveMax(&curveValues)); m_aircraft->customThrottle2Curve->initCurve(&curveValues); } else { From 594453d191746d94d562683e14e1ee2c053d5d38 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sat, 7 Jul 2012 09:00:59 -0700 Subject: [PATCH 020/543] MixerCurve, Tweek: use base curve min to init custom curve2 --- .../src/plugins/config/configvehicletypewidget.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index fbad34e22..7c8716f24 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -616,15 +616,16 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI() } else { // no, init a straight curve - m_aircraft->customThrottle1Curve->initLinearCurve(curveValues.count(),(double)1); + m_aircraft->customThrottle1Curve->initLinearCurve(curveValues.count(), 1.0); } if (MixerSettings* mxr = qobject_cast(mixer)) { MixerSettings::DataFields mixerSettingsData = mxr->getData(); if (mixerSettingsData.Curve2Source == MixerSettings::CURVE2SOURCE_THROTTLE) m_aircraft->customThrottle2Curve->setMixerType(MixerCurve::MIXERCURVE_THROTTLE); - else + else { m_aircraft->customThrottle2Curve->setMixerType(MixerCurve::MIXERCURVE_PITCH); + } } // Setup all Throttle2 curves for all types of airframes @@ -634,7 +635,7 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI() m_aircraft->customThrottle2Curve->initCurve(&curveValues); } else { - m_aircraft->customThrottle2Curve->initLinearCurve(curveValues.count(),(double)1); + m_aircraft->customThrottle2Curve->initLinearCurve(curveValues.count(), 1.0, m_aircraft->customThrottle2Curve->getMin()); } // Update the mixer table: From 0a4101c915d7e7ad357d9d2af46ac2b6537f1249 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sat, 7 Jul 2012 10:07:04 -0700 Subject: [PATCH 021/543] VehicleConfig, multirotor, slight refactor; --- .../configmultirotorwidget.cpp | 94 +++++++++---------- .../cfg_vehicletypes/configmultirotorwidget.h | 1 + .../config/cfg_vehicletypes/vehicleconfig.cpp | 13 +-- .../config/cfg_vehicletypes/vehicleconfig.h | 3 +- 4 files changed, 53 insertions(+), 58 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index 620fc54dc..dcc5dce59 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -42,7 +42,8 @@ #include "actuatorsettings.h" #include "actuatorcommand.h" -//#define Pi 3.14159265358979323846 + +const QString ConfigMultiRotorWidget::CHANNELBOXNAME = QString("multiMotorChannelBox"); /** @@ -89,10 +90,8 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) quad->setElementId("tri"); //Enable all necessary motor channel boxes... - for (i=1; i <=3; i++) { - enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } - + enableComboBoxes(uiowner, CHANNELBOXNAME, 3, true); + m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); m_aircraft->mrYawMixLevel->setValue(50); @@ -103,10 +102,8 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X")); quad->setElementId("quad-X"); - //Enable all necessary motor channel boxes... - for (i=1; i <=4; i++) { - enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + //Enable all necessary motor channel boxes... + enableComboBoxes(uiowner, CHANNELBOXNAME, 4, true); // init mixer levels m_aircraft->mrRollMixLevel->setValue(50); @@ -117,10 +114,8 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +")); quad->setElementId("quad-plus"); - //Enable all necessary motor channel boxes... - for (i=1; i <=4; i++) { - enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + //Enable all necessary motor channel boxes... + enableComboBoxes(uiowner, CHANNELBOXNAME, 4, true); m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); @@ -131,10 +126,8 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter")); quad->setElementId("quad-hexa"); - //Enable all necessary motor channel boxes... - for (i=1; i <=6; i++) { - enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + //Enable all necessary motor channel boxes... + enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true); m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(33); @@ -144,10 +137,8 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter X")); quad->setElementId("quad-hexa-H"); - //Enable all necessary motor channel boxes... - for (i=1; i <=6; i++) { - enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + //Enable all necessary motor channel boxes... + enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true); m_aircraft->mrRollMixLevel->setValue(33); m_aircraft->mrPitchMixLevel->setValue(50); @@ -159,10 +150,8 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter Y6")); quad->setElementId("hexa-coax"); - //Enable all necessary motor channel boxes... - for (i=1; i <=6; i++) { - enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + //Enable all necessary motor channel boxes... + enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true); m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(50); @@ -174,10 +163,8 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter")); quad->setElementId("quad-octo"); - //Enable all necessary motor channel boxes - for (i=1; i <=8; i++) { - enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + //Enable all necessary motor channel boxes + enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true); m_aircraft->mrRollMixLevel->setValue(33); m_aircraft->mrPitchMixLevel->setValue(33); @@ -188,10 +175,8 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter V")); quad->setElementId("quad-octo-v"); - //Enable all necessary motor channel boxes - for (i=1; i <=8; i++) { - enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + //Enable all necessary motor channel boxes + enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true); m_aircraft->mrRollMixLevel->setValue(25); m_aircraft->mrPitchMixLevel->setValue(25); @@ -203,10 +188,8 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +")); quad->setElementId("octo-coax-P"); - //Enable all necessary motor channel boxes - for (int i=1; i <=8; i++) { - enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + //Enable all necessary motor channel boxes + enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true); m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); @@ -218,10 +201,7 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X")); quad->setElementId("octo-coax-X"); - //Enable all necessary motor channel boxes - for (int i=1; i <=8; i++) { - enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true); m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(50); @@ -499,7 +479,8 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(mixer); - if (frameType == "QuadP") { + if (frameType == "QuadP") + { // Motors 1/2/3/4 are: N / E / S / W setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN); setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorE); @@ -524,7 +505,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) m_aircraft->mrRollMixLevel->setValue( -value/1.27); } - } else if (frameType == "QuadX") { + } + else if (frameType == "QuadX") + { // Motors 1/2/3/4 are: NW / NE / SE / SW setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE); @@ -548,7 +531,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) } - } else if (frameType == "Hexa") { + } + else if (frameType == "Hexa") + { // Motors 1/2/3 4/5/6 are: N / NE / SE / S / SW / NW setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN); @@ -579,7 +564,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) } - } else if (frameType == "HexaX") { + } + else if (frameType == "HexaX") + { // Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNE); @@ -606,7 +593,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); m_aircraft->mrRollMixLevel->setValue( floor(1-value/1.27) ); } - } else if (frameType == "HexaCoax") { + } + else if (frameType == "HexaCoax") + { // Motors 1/2/3 4/5/6 are: NW/W NE/E S/SE setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW); @@ -632,8 +621,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); m_aircraft->mrRollMixLevel->setValue( value/1.27); } - } else if (frameType == "Octo" || frameType == "OctoV" || - frameType == "OctoCoaxP") { + } + else if (frameType == "Octo" || frameType == "OctoV" || frameType == "OctoCoaxP") + { // Motors 1 to 8 are N / NE / E / etc setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN); @@ -689,7 +679,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) } } - } else if (frameType == "OctoCoaxX") { + } + else if (frameType == "OctoCoaxX") + { // Motors 1 to 8 are N / NE / E / etc setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW); @@ -716,7 +708,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) ); } - } else if (frameType == "Tri") { + } + else if (frameType == "Tri") + { // Motors 1 to 8 are N / NE / E / etc setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h index cb8dfa8c9..085aab106 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h @@ -66,6 +66,7 @@ private: virtual void ResetActuators(GUIConfigDataUnion* configData); static QStringList getChannelDescriptions(); + static const QString CHANNELBOXNAME; private slots: virtual void setupUI(QString airframeType); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp index fc6fe4322..1a00946ee 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp @@ -129,15 +129,16 @@ void VehicleConfig::setComboCurrentIndex(QComboBox* box, int index) /** Helper function: - enables/disables the named combobox within supplied uiowner + enables/disables the named comboboxes within supplied uiowner */ -void VehicleConfig::enableComboBox(QWidget* owner, QString boxName, bool enable) +void VehicleConfig::enableComboBoxes(QWidget* owner, QString boxName, int boxCount, bool enable) { - QComboBox* box = qFindChild(owner, boxName); - if (box) - box->setEnabled(enable); + for (int i = 1; i <= boxCount; i++) { + QComboBox* box = qFindChild(owner, QString("%0%1").arg(boxName).arg(i)); + if (box) + box->setEnabled(enable); + } } - QString VehicleConfig::getMixerType(UAVDataObject* mixer, int channel) { Q_ASSERT(mixer); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h index 7ed9d986c..2c94a045e 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h @@ -123,8 +123,7 @@ class VehicleConfig: public ConfigTaskWidget static void SetConfigData(GUIConfigDataUnion configData); static void resetField(UAVObjectField * field); static void setComboCurrentIndex(QComboBox* box, int index); - static void enableComboBox(QWidget* owner, QString boxName, bool enable); - + static void enableComboBoxes(QWidget* owner, QString boxName, int boxCount, bool enable); double getMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName); void setMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName, double value); void resetMixerVector(UAVDataObject* mixer, int channel); From 0e3236553b80307d9978b789b10ac5e1a1d2fd8e Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sat, 7 Jul 2012 12:41:43 -0700 Subject: [PATCH 022/543] Merge next conflict resolution --- .../src/plugins/config/configvehicletypewidget.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 7c8716f24..613115378 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -120,8 +120,8 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi airframeTypes << "Fixed Wing" << "Multirotor" << "Helicopter" << "Ground" << "Custom"; m_aircraft->aircraftType->addItems(airframeTypes); - m_aircraft->aircraftType->setCurrentIndex(0); //Set default vehicle to Fixedwing - m_aircraft->airframesWidget->setCurrentIndex(0); // Force the tab index to match + m_aircraft->aircraftType->setCurrentIndex(1); //Set default vehicle to MultiRotor + m_aircraft->airframesWidget->setCurrentIndex(1); // Force the tab index to match QStringList fixedWingTypes; fixedWingTypes << "Elevator aileron rudder" << "Elevon" << "Vtail"; From a6568dc4685f56d190d48fb10e7afd2f84cbb9fc Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sat, 7 Jul 2012 12:47:07 -0700 Subject: [PATCH 023/543] merge next conflict resolution --- .../openpilotgcs/src/plugins/config/configvehicletypewidget.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 613115378..01de2d1b0 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -119,7 +119,6 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi QStringList airframeTypes; airframeTypes << "Fixed Wing" << "Multirotor" << "Helicopter" << "Ground" << "Custom"; m_aircraft->aircraftType->addItems(airframeTypes); - m_aircraft->aircraftType->setCurrentIndex(1); //Set default vehicle to MultiRotor m_aircraft->airframesWidget->setCurrentIndex(1); // Force the tab index to match From 13cd6c56f7360ea23ebfd77facf98deb3c4e631e Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sat, 7 Jul 2012 17:49:51 -0700 Subject: [PATCH 024/543] bugfix: correct spelling, multirotor widget --- ground/openpilotgcs/src/plugins/config/airframe.ui | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 82097b90b..1e2e15b03 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -859,7 +859,7 @@ margin:1px; - Throtte Curve + Throttle Curve From a328ab997351ef4bb0fd11b36ba1726f8b6e5ca9 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sat, 7 Jul 2012 21:56:07 -0700 Subject: [PATCH 025/543] Bugfix: step curvetype; Tweek: adjust node value position and color. --- .../src/plugins/config/mixercurve.cpp | 6 ++++-- .../uavobjectwidgetutils/mixercurveline.cpp | 2 +- .../uavobjectwidgetutils/mixercurvepoint.cpp | 16 +++++++++++----- .../uavobjectwidgetutils/mixercurvewidget.cpp | 2 +- 4 files changed, 17 insertions(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index bacc01e98..3a9306759 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -147,7 +147,9 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->CurveMax->setVisible(true); m_mixerUI->stepLabel->setText("Step at"); m_mixerUI->stepLabel->setVisible(true); - m_mixerUI->CurveStep->setVisible(true); + m_mixerUI->CurveStep->setVisible(true); + + m_mixerUI->CurveStep->setMinimum(1.0); m_mixerUI->CurveStep->setMaximum(4.0); } if ( curveType.compare("Exp")==0) @@ -202,7 +204,7 @@ void MixerCurve::GenerateCurve() } if ( CurveType.compare("Step")==0) { - if (scale*100 qreal(20.)) { - QPointF edgeOffset((line.dx() * 10) / length, (line.dy() * 10) / length); + QPointF edgeOffset((line.dx() * 13) / length, (line.dy() * 13) / length); sourcePoint = line.p1() + edgeOffset; destPoint = line.p2() - edgeOffset; } else { diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp index 199a0dba5..1187b898f 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp @@ -59,13 +59,13 @@ QList Node::edges() const QRectF Node::boundingRect() const { - return QRectF(-12, -12, 25, 25); + return QRectF(-13, -13, 26, 26); } QPainterPath Node::shape() const { QPainterPath path; - path.addEllipse(-12, -12, 25, 25); + path.addEllipse(-13, -13, 26, 26); return path; } @@ -89,10 +89,16 @@ void Node::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWid } painter->setBrush(gradient); painter->setPen(QPen(Qt::black, 0)); - painter->drawEllipse(-12, -12, 25, 25); + painter->drawEllipse(-13, -13, 26, 26); - painter->setPen(QPen(Qt::white, 0)); - painter->drawText(-10, 3, QString().sprintf("%.2f", value())); + if (value() < 0) { + painter->setPen(QPen(Qt::red, 0)); + painter->drawText(-12, 4, QString().sprintf("%.2f", value())); + } + else { + painter->setPen(QPen(Qt::white, 0)); + painter->drawText(-11, 4, QString().sprintf("%.2f", value())); + } } void Node::verticalMove(bool flag){ diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index 543d85151..110131ae4 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -239,7 +239,7 @@ void MixerCurveWidget::showEvent(QShowEvent *event) QRectF rect = plot->boundingRect(); - fitInView(rect.adjusted(-12,-12,12,12), Qt::KeepAspectRatio); + fitInView(rect.adjusted(-15,-15,15,15), Qt::KeepAspectRatio); } void MixerCurveWidget::resizeEvent(QResizeEvent* event) From 9f9d294f6c673618b782192fa4c12410fd5e3822 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sun, 8 Jul 2012 16:43:47 +0200 Subject: [PATCH 026/543] OP-359 Fixed colors, hilight time and meta data state bug when switching using scientific editors and not. --- .../uavobjectbrowser/uavobjectbrowserwidget.cpp | 4 ++++ .../plugins/uavobjectbrowser/uavobjectbrowserwidget.h | 10 +++++++--- 2 files changed, 11 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp index b7d0644dc..91111fd76 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp @@ -89,7 +89,11 @@ void UAVObjectBrowserWidget::useScientificNotation(bool scientific) UAVObjectTreeModel* tmpModel = m_model; m_model = new UAVObjectTreeModel(0, scientific); + m_model->setRecentlyUpdatedColor(m_recentlyUpdatedColor); + m_model->setManuallyChangedColor(m_manuallyChangedColor); + m_model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout); m_browser->treeView->setModel(m_model); + showMetaData(m_browser->metaCheckBox->isChecked()); delete tmpModel; } diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h index cd058dadc..5b0d3a7f6 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h @@ -45,9 +45,9 @@ class UAVObjectBrowserWidget : public QWidget public: UAVObjectBrowserWidget(QWidget *parent = 0); ~UAVObjectBrowserWidget(); - void setRecentlyUpdatedColor(QColor color) { m_model->setRecentlyUpdatedColor(color); } - void setManuallyChangedColor(QColor color) { m_model->setManuallyChangedColor(color); } - void setRecentlyUpdatedTimeout(int timeout) { m_model->setRecentlyUpdatedTimeout(timeout); } + void setRecentlyUpdatedColor(QColor color) { m_recentlyUpdatedColor = color; m_model->setRecentlyUpdatedColor(color); } + void setManuallyChangedColor(QColor color) { m_manuallyChangedColor = color; m_model->setManuallyChangedColor(color); } + void setRecentlyUpdatedTimeout(int timeout) { m_recentlyUpdatedTimeout = timeout; m_model->setRecentlyUpdatedTimeout(timeout); } public slots: void showMetaData(bool show); @@ -67,6 +67,10 @@ private: Ui_UAVObjectBrowser *m_browser; UAVObjectTreeModel *m_model; + int m_recentlyUpdatedTimeout; + QColor m_recentlyUpdatedColor; + QColor m_manuallyChangedColor; + void updateObjectPersistance(ObjectPersistence::OperationOptions op, UAVObject *obj); void enableSendRequest(bool enable); ObjectTreeItem *findCurrentObjectTreeItem(); From ea6076968017ca0115ec1fcf07ff10b32627789b Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sun, 8 Jul 2012 10:38:15 -0700 Subject: [PATCH 027/543] Tweeks: restore 'step' curve logic to original; adjust node text position, clipping; --- .../src/plugins/config/mixercurve.cpp | 3 +-- .../uavobjectwidgetutils/mixercurvepoint.cpp | 22 +++++++++++++------ .../uavobjectwidgetutils/mixercurvewidget.cpp | 2 +- 3 files changed, 17 insertions(+), 10 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 3a9306759..d8d3c8f95 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -150,7 +150,6 @@ void MixerCurve::UpdateCurveUI() m_mixerUI->CurveStep->setVisible(true); m_mixerUI->CurveStep->setMinimum(1.0); - m_mixerUI->CurveStep->setMaximum(4.0); } if ( curveType.compare("Exp")==0) { @@ -204,7 +203,7 @@ void MixerCurve::GenerateCurve() } if ( CurveType.compare("Step")==0) { - if (i < value3) //(scale*100state & QStyle::State_Sunken) { gradient.setCenter(3, 3); gradient.setFocalPoint(3, 3); - gradient.setColorAt(1, QColor("#1c870b").light(120)); - gradient.setColorAt(0, QColor("#116703").light(120)); + //gradient.setColorAt(1, QColor("#1c870b").light(120)); + //gradient.setColorAt(0, QColor("#116703").light(120)); + + gradient.setColorAt(1, Qt::darkBlue); + gradient.setColorAt(0, Qt::darkBlue); } else { - gradient.setColorAt(0, "#1c870b"); - gradient.setColorAt(1, "#116703"); + if (value() < 0) { + gradient.setColorAt(0, Qt::red); + gradient.setColorAt(1, Qt::red); + } + else { + gradient.setColorAt(0, "#1c870b"); + gradient.setColorAt(1, "#116703"); + } } painter->setBrush(gradient); painter->setPen(QPen(Qt::black, 0)); painter->drawEllipse(-13, -13, 26, 26); + painter->setPen(QPen(Qt::white, 0)); if (value() < 0) { - painter->setPen(QPen(Qt::red, 0)); - painter->drawText(-12, 4, QString().sprintf("%.2f", value())); + painter->drawText(-13, 4, QString().sprintf("% .2f", value())); } else { - painter->setPen(QPen(Qt::white, 0)); painter->drawText(-11, 4, QString().sprintf("%.2f", value())); } } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index 110131ae4..3833b18ed 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -248,7 +248,7 @@ void MixerCurveWidget::resizeEvent(QResizeEvent* event) QRectF rect = plot->boundingRect(); - fitInView(rect.adjusted(-12,-12,12,12), Qt::KeepAspectRatio); + fitInView(rect.adjusted(-15,-15,15,15), Qt::KeepAspectRatio); } void MixerCurveWidget::itemMoved(double itemValue) From 9c716abb11cda60976fbb1c3d57b173e7b3b03e9 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sun, 8 Jul 2012 18:34:23 -0700 Subject: [PATCH 028/543] Bugfixes: get both confighardware and firmware widgets to show CC3D image if detected. --- .../plugins/config/config_cc_hw_widget.cpp | 24 ++++++++++++++++++- .../plugins/uploader/runningdevicewidget.cpp | 3 +++ 2 files changed, 26 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp index 97cfccd47..4af991a6e 100644 --- a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp @@ -41,8 +41,30 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent) m_telemetry = new Ui_CC_HW_Widget(); m_telemetry->setupUi(this); - m_telemetry->label_2->setPixmap(QPixmap(":/configgadget/images/coptercontrol.svg")); + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectUtilManager* utilMngr = pm->getObject(); + int id = utilMngr->getBoardModel(); + switch (id) { + case 0x0101: + m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0101.svg")); + break; + case 0x0301: + m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0301.svg")); + break; + case 0x0401: + m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0401.svg")); + break; + case 0x0402: + m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0402.svg")); + break; + case 0x0201: + m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0201.svg")); + break; + default: + m_telemetry->label_2->setPixmap(QPixmap(":/configgadget/images/coptercontrol.svg")); + break; + } addApplySaveButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD); addUAVObjectToWidgetRelation("HwSettings","CC_FlexiPort",m_telemetry->cbFlexi); addUAVObjectToWidgetRelation("HwSettings","CC_MainPort",m_telemetry->cbTele); diff --git a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp index 4bf17e615..145e0f322 100644 --- a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp @@ -94,6 +94,9 @@ void runningDeviceWidget::populate() case 0x0401: devicePic->renderer()->load(QString(":/uploader/images/deviceID-0401.svg")); break; + case 0x0402: + devicePic->renderer()->load(QString(":/uploader/images/deviceID-0402.svg")); + break; case 0x0201: devicePic->renderer()->load(QString(":/uploader/images/deviceID-0201.svg")); break; From 898bd7dbf168591f15246c72b68878817a9b378b Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 9 Jul 2012 08:59:52 -0700 Subject: [PATCH 029/543] rename doublespindelegate files --- .../src/plugins/config/DoubleSpinDelegate.cpp | 86 ------------------- .../src/plugins/config/DoubleSpinDelegate.h | 74 ---------------- .../src/plugins/config/config.pro | 4 +- .../src/plugins/config/mixercurve.cpp | 2 +- .../src/plugins/config/mixercurve.h | 2 +- 5 files changed, 4 insertions(+), 164 deletions(-) delete mode 100644 ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.cpp delete mode 100644 ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.h diff --git a/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.cpp b/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.cpp deleted file mode 100644 index d87cdfd70..000000000 --- a/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.cpp +++ /dev/null @@ -1,86 +0,0 @@ -/** - ****************************************************************************** - * - * @file doublespindelegate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup ConfigPlugin Config Plugin - * @{ - * @brief A double spinbox delegate - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "doublespindelegate.h" - -/** - Helper delegate for the custom mixer editor table. - */ -DoubleSpinDelegate::DoubleSpinDelegate(QObject *parent) - : QItemDelegate(parent) - { - m_min = 0.0; - m_max = 1.0; - m_decimals = 2; - m_step = 0.01; - } - -QWidget *DoubleSpinDelegate::createEditor(QWidget *parent, - const QStyleOptionViewItem &/* option */, - const QModelIndex &/* index */) const -{ - QDoubleSpinBox *editor = new QDoubleSpinBox(parent); - editor->setMinimum(m_min); - editor->setMaximum(m_max); - editor->setDecimals(m_decimals); - editor->setSingleStep(m_step); - - connect(editor,SIGNAL(valueChanged(double)), this, SLOT(valueChanged())); - - return editor; -} - -void DoubleSpinDelegate::setEditorData(QWidget *editor, - const QModelIndex &index) const -{ - double value = index.model()->data(index, Qt::EditRole).toDouble(); - - QDoubleSpinBox *spinBox = static_cast(editor); - spinBox->setValue(value); -} - -void DoubleSpinDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, - const QModelIndex &index) const -{ - QDoubleSpinBox *spinBox = static_cast(editor); - spinBox->interpretText(); - double value = spinBox->value(); - - model->setData(index, value, Qt::EditRole); -} - -void DoubleSpinDelegate::updateEditorGeometry(QWidget *editor, - const QStyleOptionViewItem &option, const QModelIndex &/* index */) const -{ - editor->setGeometry(option.rect); -} - -void DoubleSpinDelegate::valueChanged() -{ - emit ValueChanged(); -} - diff --git a/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.h b/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.h deleted file mode 100644 index 0711cf81d..000000000 --- a/ground/openpilotgcs/src/plugins/config/DoubleSpinDelegate.h +++ /dev/null @@ -1,74 +0,0 @@ -/** - ****************************************************************************** - * - * @file doublespindelegate.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup ConfigPlugin Config Plugin - * @{ - * @brief A double spinbox delegate - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef DOUBLESPINDELEGATE_H -#define DOUBLESPINDELEGATE_H - -#include -#include - - -namespace Ui { -class DoubleSpinDelegate; -} - -class DoubleSpinDelegate : public QItemDelegate -{ - Q_OBJECT - -public: - DoubleSpinDelegate(QObject *parent = 0); - - QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &option, - const QModelIndex &index) const; - - void setEditorData(QWidget *editor, const QModelIndex &index) const; - void setModelData(QWidget *editor, QAbstractItemModel *model, - const QModelIndex &index) const; - - void updateEditorGeometry(QWidget *editor, - const QStyleOptionViewItem &option, const QModelIndex &index) const; - - void setMin(double min) { m_min = min; } - void setMax(double max) { m_max = max; } - void setRange(double min, double max) { m_min = min; m_max = max; } - void setStep(double step) { m_step = step; } - void setDecimals(int decimals) { m_decimals = decimals; } - -private: - double m_min; - double m_max; - double m_step; - int m_decimals; - -signals: - void ValueChanged(); - -private slots: - void valueChanged() ; -}; - -#endif // DOUBLESPINDELEGATE_H diff --git a/ground/openpilotgcs/src/plugins/config/config.pro b/ground/openpilotgcs/src/plugins/config/config.pro index af38ef4ce..af6f3e1ed 100644 --- a/ground/openpilotgcs/src/plugins/config/config.pro +++ b/ground/openpilotgcs/src/plugins/config/config.pro @@ -38,7 +38,7 @@ HEADERS += configplugin.h \ configrevowidget.h \ config_global.h \ mixercurve.h \ - doublespindelegate.h + dblspindelegate.h SOURCES += configplugin.cpp \ configgadgetconfiguration.cpp \ configgadgetwidget.cpp \ @@ -71,7 +71,7 @@ SOURCES += configplugin.cpp \ outputchannelform.cpp \ cfg_vehicletypes/vehicleconfig.cpp \ mixercurve.cpp \ - doublespindelegate.cpp + dblspindelegate.cpp FORMS += airframe.ui \ cc_hw_settings.ui \ pro_hw_settings.ui \ diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index d8d3c8f95..e8da7dbaa 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -29,7 +29,7 @@ #include #include #include "mixercurve.h" -#include "doublespindelegate.h" +#include "dblspindelegate.h" MixerCurve::MixerCurve(QWidget *parent) : QFrame(parent), diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.h b/ground/openpilotgcs/src/plugins/config/mixercurve.h index 1cda78284..f746dfec7 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.h +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.h @@ -34,7 +34,7 @@ #include "ui_mixercurve.h" #include "mixercurvewidget.h" -#include "doublespindelegate.h" +#include "dblspindelegate.h" #include "uavobjectwidgetutils_global.h" From 923345762b0eff2cd970a3ea9c39e9b7692c00a5 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 9 Jul 2012 09:07:22 -0700 Subject: [PATCH 030/543] mixercurve, dblspindelegate names --- .../src/plugins/config/dblspindelegate.cpp | 86 +++++++++++++++++++ .../src/plugins/config/dblspindelegate.h | 73 ++++++++++++++++ 2 files changed, 159 insertions(+) create mode 100644 ground/openpilotgcs/src/plugins/config/dblspindelegate.cpp create mode 100644 ground/openpilotgcs/src/plugins/config/dblspindelegate.h diff --git a/ground/openpilotgcs/src/plugins/config/dblspindelegate.cpp b/ground/openpilotgcs/src/plugins/config/dblspindelegate.cpp new file mode 100644 index 000000000..21af3f1d2 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/dblspindelegate.cpp @@ -0,0 +1,86 @@ +/** + ****************************************************************************** + * + * @file doublespindelegate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief A double spinbox delegate + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "dblspindelegate.h" + +/** + Helper delegate for the custom mixer editor table. + */ +DoubleSpinDelegate::DoubleSpinDelegate(QObject *parent) + : QItemDelegate(parent) + { + m_min = 0.0; + m_max = 1.0; + m_decimals = 2; + m_step = 0.01; + } + +QWidget *DoubleSpinDelegate::createEditor(QWidget *parent, + const QStyleOptionViewItem &/* option */, + const QModelIndex &/* index */) const +{ + QDoubleSpinBox *editor = new QDoubleSpinBox(parent); + editor->setMinimum(m_min); + editor->setMaximum(m_max); + editor->setDecimals(m_decimals); + editor->setSingleStep(m_step); + + connect(editor,SIGNAL(valueChanged(double)), this, SLOT(valueChanged())); + + return editor; +} + +void DoubleSpinDelegate::setEditorData(QWidget *editor, + const QModelIndex &index) const +{ + double value = index.model()->data(index, Qt::EditRole).toDouble(); + + QDoubleSpinBox *spinBox = static_cast(editor); + spinBox->setValue(value); +} + +void DoubleSpinDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, + const QModelIndex &index) const +{ + QDoubleSpinBox *spinBox = static_cast(editor); + spinBox->interpretText(); + double value = spinBox->value(); + + model->setData(index, value, Qt::EditRole); +} + +void DoubleSpinDelegate::updateEditorGeometry(QWidget *editor, + const QStyleOptionViewItem &option, const QModelIndex &/* index */) const +{ + editor->setGeometry(option.rect); +} + +void DoubleSpinDelegate::valueChanged() +{ + emit ValueChanged(); +} + diff --git a/ground/openpilotgcs/src/plugins/config/dblspindelegate.h b/ground/openpilotgcs/src/plugins/config/dblspindelegate.h new file mode 100644 index 000000000..482a07649 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/dblspindelegate.h @@ -0,0 +1,73 @@ +/** + ****************************************************************************** + * + * @file doublespindelegate.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief A double spinbox delegate + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef DOUBLESPINDELEGATE_H +#define DOUBLESPINDELEGATE_H + +#include +#include + +namespace Ui { +class DoubleSpinDelegate; +} + +class DoubleSpinDelegate : public QItemDelegate +{ + Q_OBJECT + +public: + DoubleSpinDelegate(QObject *parent = 0); + + QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &option, + const QModelIndex &index) const; + + void setEditorData(QWidget *editor, const QModelIndex &index) const; + void setModelData(QWidget *editor, QAbstractItemModel *model, + const QModelIndex &index) const; + + void updateEditorGeometry(QWidget *editor, + const QStyleOptionViewItem &option, const QModelIndex &index) const; + + void setMin(double min) { m_min = min; } + void setMax(double max) { m_max = max; } + void setRange(double min, double max) { m_min = min; m_max = max; } + void setStep(double step) { m_step = step; } + void setDecimals(int decimals) { m_decimals = decimals; } + +private: + double m_min; + double m_max; + double m_step; + int m_decimals; + +signals: + void ValueChanged(); + +private slots: + void valueChanged(); +}; + +#endif // DOUBLESPINDELEGATE_H From 532fc3071a9fb850bdb97f0b030937f835f38d34 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Tue, 10 Jul 2012 00:26:59 +0200 Subject: [PATCH 031/543] OP-39 Initial commit. Created new sub project to plugins project. Added plug-in and registering menu item to start the wizard. Created SetupWizard sub class of QWizard to host logic for wizard traversal and data collection. --- ground/openpilotgcs/src/plugins/plugins.pro | 7 ++ .../setupwizard/SetupWizard.pluginspec | 10 +++ .../src/plugins/setupwizard/setupwizard.cpp | 37 ++++++++ .../src/plugins/setupwizard/setupwizard.h | 41 +++++++++ .../src/plugins/setupwizard/setupwizard.pro | 13 +++ .../plugins/setupwizard/setupwizardplugin.cpp | 85 +++++++++++++++++++ .../plugins/setupwizard/setupwizardplugin.h | 50 +++++++++++ 7 files changed, 243 insertions(+) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/SetupWizard.pluginspec create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h diff --git a/ground/openpilotgcs/src/plugins/plugins.pro b/ground/openpilotgcs/src/plugins/plugins.pro index 154335e3a..c2c7c922b 100644 --- a/ground/openpilotgcs/src/plugins/plugins.pro +++ b/ground/openpilotgcs/src/plugins/plugins.pro @@ -210,6 +210,13 @@ plugin_uavobjectwidgetutils.depends += plugin_uavobjects plugin_uavobjectwidgetutils.depends += plugin_uavsettingsimportexport SUBDIRS += plugin_uavobjectwidgetutils +# Setup Wizard plugin +plugin_setupwizard.subdir = setupwizard +plugin_setupwizard.depends = plugin_coreplugin +plugin_setupwizard.depends += plugin_uavobjects +plugin_setupwizard.depends += plugin_uavsettingsimportexport +SUBDIRS += plugin_setupwizard + # Junsi Powerlog plugin #plugin_powerlog.subdir = powerlog #plugin_powerlog.depends = plugin_coreplugin diff --git a/ground/openpilotgcs/src/plugins/setupwizard/SetupWizard.pluginspec b/ground/openpilotgcs/src/plugins/setupwizard/SetupWizard.pluginspec new file mode 100644 index 000000000..4425b290e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/SetupWizard.pluginspec @@ -0,0 +1,10 @@ + + The OpenPilot Project + (C) 2012 OpenPilot Project + The GNU Public License (GPL) Version 3 + A plugin that provides a setup wizard for easy initial setup of airframes. + http://www.openpilot.org + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp new file mode 100644 index 000000000..1513b40b2 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -0,0 +1,37 @@ +/** + ****************************************************************************** + * + * @file setupwizard.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup Setup Wizard Plugin + * @{ + * @brief A Wizards to make the initial setup easy for everyone. + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "setupwizard.h" + +SetupWizard::SetupWizard(QWidget *parent) : QWizard(parent) +{ + setWindowTitle("GCS Setup Wizard"); + QWizardPage* page = new QWizardPage(); + page->setFixedSize(300, 300); + addPage(page); +} + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h new file mode 100644 index 000000000..7bd907cad --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -0,0 +1,41 @@ +/** + ****************************************************************************** + * + * @file setupwizard.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup Setup Wizard Plugin + * @{ + * @brief A Wizards to make the initial setup easy for everyone. + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef SETUPWIZARD_H +#define SETUPWIZARD_H + +#include + +class SetupWizard : public QWizard +{ + Q_OBJECT + +public: + SetupWizard(QWidget *parent = 0); +}; + +#endif // SETUPWIZARD_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro new file mode 100644 index 000000000..cc5122a25 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -0,0 +1,13 @@ + +TEMPLATE = lib +TARGET = SetupWizard + +include(../../openpilotgcsplugin.pri) +include(../../plugins/coreplugin/coreplugin.pri) + +HEADERS += setupwizardplugin.h \ + setupwizard.h +SOURCES += setupwizardplugin.cpp \ + setupwizard.cpp + +OTHER_FILES += SetupWizard.pluginspec \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp new file mode 100644 index 000000000..5ac0b4c6c --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp @@ -0,0 +1,85 @@ +/** + ****************************************************************************** + * + * @file donothingplugin.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup SetupWizardPlugin Do Nothing Plugin + * @{ + * @brief A Setup Wizard Plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "setupwizardplugin.h" + +#include +#include +#include +#include + +#include +#include +#include +#include + +SetupWizardPlugin::SetupWizardPlugin() +{ + // Do nothing +} + +SetupWizardPlugin::~SetupWizardPlugin() +{ +} + +bool SetupWizardPlugin::initialize(const QStringList& args, QString *errMsg) +{ + Q_UNUSED(args); + Q_UNUSED(errMsg); + + // Add Menu entry + Core::ActionManager* am = Core::ICore::instance()->actionManager(); + Core::ActionContainer* ac = am->actionContainer(Core::Constants::M_TOOLS); + + Core::Command* cmd = am->registerAction(new QAction(this), + "SetupWizardPlugin.ShowSetupWizard", + QList() << + Core::Constants::C_GLOBAL_ID); + cmd->setDefaultKeySequence(QKeySequence("Ctrl+W")); + cmd->action()->setText(tr("GCS Setup Wizard")); + + ac->menu()->addSeparator(); + ac->appendGroup("Wizard"); + ac->addAction(cmd, "Wizard"); + + connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(showSetupWizard())); + return true; +} + +void SetupWizardPlugin::extensionsInitialized() +{ +} + +void SetupWizardPlugin::shutdown() +{ +} + +void SetupWizardPlugin::showSetupWizard() +{ + SetupWizard().exec(); +} + +Q_EXPORT_PLUGIN(SetupWizardPlugin) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h new file mode 100644 index 000000000..dcff10a60 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h @@ -0,0 +1,50 @@ +/** + ****************************************************************************** + * + * @file donothingplugin.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DoNothingPlugin Do Nothing Plugin + * @{ + * @brief A minimal example plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef SETUPWIZARDPLUGIN_H +#define SETUPWIZARDPLUGIN_H + +#include +#include +#include "setupwizard.h" + +class SetupWizardPlugin : public ExtensionSystem::IPlugin +{ + Q_OBJECT +public: + SetupWizardPlugin(); + ~SetupWizardPlugin(); + + void extensionsInitialized(); + bool initialize(const QStringList & arguments, QString * errorString); + void shutdown(); + +private slots: + void showSetupWizard(); + +}; + +#endif // SETUPWIZARDPLUGIN_H From 0c6bd52a5769e6e26febead5d739af084fd0178b Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 9 Jul 2012 21:34:31 -0700 Subject: [PATCH 032/543] Tweek: ConfigInputWidget, change default flightmode for fm1 from Manual to Stabilized1; result of changing aircraft default to multirotor. --- .../src/plugins/config/configinputwidget.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index 7952b3d70..a74bf037d 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -82,12 +82,12 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent) connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack())); m_config->stackedWidget->setCurrentIndex(0); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,3); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,4); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,5); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,1); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,2); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,3); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,1); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,2); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,3); addUAVObjectToWidgetRelation("ManualControlSettings","FlightModeNumber",m_config->fmsPosNum); addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Roll,"Roll"); From 559be15142c5d6ef425b855aeee673a181ad023f Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Wed, 11 Jul 2012 01:00:41 +0200 Subject: [PATCH 033/543] OP-39 Start and End pages added. Placeholder text added. --- .../src/plugins/setupwizard/pages/endpage.cpp | 15 ++++ .../src/plugins/setupwizard/pages/endpage.h | 22 +++++ .../src/plugins/setupwizard/pages/endpage.ui | 80 +++++++++++++++++++ .../plugins/setupwizard/pages/startpage.cpp | 14 ++++ .../src/plugins/setupwizard/pages/startpage.h | 22 +++++ .../plugins/setupwizard/pages/startpage.ui | 56 +++++++++++++ .../src/plugins/setupwizard/setupwizard.cpp | 27 +++++-- .../src/plugins/setupwizard/setupwizard.h | 8 +- .../src/plugins/setupwizard/setupwizard.pro | 14 +++- .../plugins/setupwizard/setupwizardplugin.cpp | 4 +- .../plugins/setupwizard/setupwizardplugin.h | 4 +- 11 files changed, 252 insertions(+), 14 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp new file mode 100644 index 000000000..3270e23ff --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp @@ -0,0 +1,15 @@ +#include "endpage.h" +#include "ui_endpage.h" + +EndPage::EndPage(QWidget *parent) : + QWizardPage(parent), + ui(new Ui::EndPage) +{ + setFinalPage(true); + ui->setupUi(this); +} + +EndPage::~EndPage() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h new file mode 100644 index 000000000..e4179e677 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h @@ -0,0 +1,22 @@ +#ifndef ENDPAGE_H +#define ENDPAGE_H + +#include + +namespace Ui { +class EndPage; +} + +class EndPage : public QWizardPage +{ + Q_OBJECT + +public: + explicit EndPage(QWidget *parent = 0); + ~EndPage(); + +private: + Ui::EndPage *ui; +}; + +#endif // ENDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui new file mode 100644 index 000000000..cc0a5c162 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui @@ -0,0 +1,80 @@ + + + EndPage + + + + 0 + 0 + 600 + 400 + + + + + 600 + 400 + + + + WizardPage + + + + + 20 + 20 + 550 + 141 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Setup complete</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">The wizard have now gathered enough information to create a baseline configuration for your OpenPilot controller board to use with your vehicle.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">You now have two choices:</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">- Upload configuration directly to the currently connected OpenPilot controller board.</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">- Save the configuration to a file for later uploading using the configuration import plugin in GCS.</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + 420 + 290 + 125 + 23 + + + + Save configuration... + + + + + + 420 + 340 + 125 + 23 + + + + Uppload configuration + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp new file mode 100644 index 000000000..f36631bb0 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp @@ -0,0 +1,14 @@ +#include "startpage.h" +#include "ui_startpage.h" + +StartPage::StartPage(QWidget *parent) : + QWizardPage(parent), + ui(new Ui::StartPage) +{ + ui->setupUi(this); +} + +StartPage::~StartPage() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h new file mode 100644 index 000000000..f6cf9b6cd --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h @@ -0,0 +1,22 @@ +#ifndef STARTPAGE_H +#define STARTPAGE_H + +#include + +namespace Ui { +class StartPage; +} + +class StartPage : public QWizardPage +{ + Q_OBJECT + +public: + explicit StartPage(QWidget *parent = 0); + ~StartPage(); + +private: + Ui::StartPage *ui; +}; + +#endif // STARTPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui new file mode 100644 index 000000000..0f656f35c --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui @@ -0,0 +1,56 @@ + + + StartPage + + + + 0 + 0 + 640 + 400 + + + + + 640 + 400 + + + + WizardPage + + + + + 20 + 20 + 550 + 350 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Welcome to the OpenPilot Setup Wizard</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This wizard will guide you through the basic steps of setting up your OpenPilot controller board. The following pages contains simple questions about your vehicle and its characteristics. </span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">From the information </span><span style=" font-size:10pt;">gathered</span><span style=" font-size:10pt;"> the wizard will create a baseline configuration that should be good enough for you to get a quick start using your OpenPilot product.</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">The baseline configuration can, if desired, be uploaded to the OpenPilot Controller board at the end of this wizard.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This wizard does not contain the full range of settings available in the GCS Config plugin. All configuration parameters can be changed at later by using the GCS Config plugin.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Ok, lets start the configuration by clicking on the 'Next' button below.</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 1513b40b2..26a5e386a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -7,7 +7,7 @@ * @{ * @addtogroup Setup Wizard Plugin * @{ - * @brief A Wizards to make the initial setup easy for everyone. + * @brief A Wizard to make the initial setup easy for everyone. *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -26,12 +26,29 @@ */ #include "setupwizard.h" +#include "pages/startpage.h" +#include "pages/endpage.h" SetupWizard::SetupWizard(QWidget *parent) : QWizard(parent) { - setWindowTitle("GCS Setup Wizard"); - QWizardPage* page = new QWizardPage(); - page->setFixedSize(300, 300); - addPage(page); + setWindowTitle("OpenPilot Setup Wizard"); + createPages(); } +int SetupWizard::nextId() const +{ + switch (currentId()) { + case PAGE_START: + return PAGE_END; + default: + return -1; + } +} + +void SetupWizard::createPages() +{ + setPage(PAGE_START, new StartPage()); + setPage(PAGE_END, new EndPage()); + + setStartId(PAGE_START); +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h index 7bd907cad..42f75556a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -32,10 +32,14 @@ class SetupWizard : public QWizard { - Q_OBJECT + Q_OBJECT public: - SetupWizard(QWidget *parent = 0); + SetupWizard(QWidget *parent = 0); + int nextId() const; +private: + enum {PAGE_START, PAGE_END}; + void createPages(); }; #endif // SETUPWIZARD_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index cc5122a25..20d13155d 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -6,8 +6,16 @@ include(../../openpilotgcsplugin.pri) include(../../plugins/coreplugin/coreplugin.pri) HEADERS += setupwizardplugin.h \ - setupwizard.h + setupwizard.h \ + pages/startpage.h \ + pages/endpage.h SOURCES += setupwizardplugin.cpp \ - setupwizard.cpp + setupwizard.cpp \ + pages/startpage.cpp \ + pages/endpage.cpp -OTHER_FILES += SetupWizard.pluginspec \ No newline at end of file +OTHER_FILES += SetupWizard.pluginspec + +FORMS += \ + pages/startpage.ui \ + pages/endpage.ui \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp index 5ac0b4c6c..a6dddbd4c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp @@ -5,7 +5,7 @@ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup SetupWizardPlugin Do Nothing Plugin + * @addtogroup SetupWizardPlugin * @{ * @brief A Setup Wizard Plugin *****************************************************************************/ @@ -59,7 +59,7 @@ bool SetupWizardPlugin::initialize(const QStringList& args, QString *errMsg) QList() << Core::Constants::C_GLOBAL_ID); cmd->setDefaultKeySequence(QKeySequence("Ctrl+W")); - cmd->action()->setText(tr("GCS Setup Wizard")); + cmd->action()->setText(tr("OpenPilot Setup Wizard")); ac->menu()->addSeparator(); ac->appendGroup("Wizard"); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h index dcff10a60..4caecbcd0 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h @@ -5,9 +5,9 @@ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup DoNothingPlugin Do Nothing Plugin + * @addtogroup SetupWizardPlugin * @{ - * @brief A minimal example plugin + * @brief A Setup Wizard Plugin *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify From 9d32e1789b379e385c914576b293ad6e23d66425 Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Tue, 10 Jul 2012 20:53:31 -0700 Subject: [PATCH 034/543] UI changes to the GCS interface pages --- .../src/plugins/config/airframe.ui | 5319 +- .../src/plugins/config/camerastabilization.ui | 1599 +- .../config/configstabilizationwidget.cpp | 8 +- .../openpilotgcs/src/plugins/config/input.ui | 1760 +- .../src/plugins/config/inputchannelform.ui | 4 +- .../openpilotgcs/src/plugins/config/output.ui | 1077 +- .../src/plugins/config/stabilization.ui | 46438 ++++++++-------- .../openpilotgcs/src/plugins/config/txpid.ui | 1071 +- 8 files changed, 28715 insertions(+), 28561 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 47006a789..0018812be 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -6,14 +6,17 @@ 0 0 - 796 - 618 + 828 + 1007 Form - + + + 12 + @@ -23,581 +26,97 @@ Mixer Settings - + - 5 + 12 - - - - - - 75 - true - - - - Vehicle type: - - - - - - - Select aircraft type here - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Horizontal + + + QFrame::NoFrame - - - - - - 0 + + true - - - true + + + + 0 + 0 + 782 + 835 + - - false - - + - + - - - - - - 0 - 0 - - - - - 75 - true - - - - Airplane type: - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - + + + + 75 + true + + + + Vehicle type: + + - + + + Select aircraft type here + + - - - - - - 0 - 0 - - - - - 230 - 100 - - - - Output Channel Assignments - - - - - - Engine - - - - - - - Select output channel for the engine - - - - - - - - 60 - 0 - - - - Aileron 1 - - - - - - - Select output channel for the first aileron (or elevon) - - - - - - - false - - - - 60 - 0 - - - - Aileron 2 - - - - - - - false - - - Select output channel for the second aileron (or elevon) - - - - - - - - 67 - 0 - - - - Elevator 1 - - - - - - - Select output channel for the first elevator - - - - - - - false - - - - 67 - 0 - - - - Elevator 2 - - - - - - - false - - - Select output channel for a secondary elevator - - - - - - - Rudder 1 - - - - - - - Select output channel for the first rudder - - - - - - - Rudder 2 - - - - - - - Select output channel for a secondary rudder - - - - - - - Qt::Vertical - - - - 20 - 20 - - - - - - - - - - - - 0 - 0 - - - - Elevon Mix - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 0 - 20 - - - - - - - - - - - - - 65 - 0 - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Rudder % - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - 100 - - - 50 - - - Qt::Vertical - - - - - - - 50 - - - Qt::AlignCenter - - - - - - - - - - - - 50 - 0 - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Pitch % - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - 100 - - - 50 - - - Qt::Vertical - - - - - - - 50 - - - Qt::AlignCenter - - - - - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 100 - - - - Throttle Curve - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 20 - - - - - - - - - 0 - 0 - - - - - 100 - 100 - - - - - 200 - 200 - - - - - 10 - 10 - - - - - - - - - 200 - 16777215 - - - - Reset - - - - - - - Val: 0.00 - - - - - - - - - - + - Qt::Vertical + Qt::Horizontal - 20 - 40 + 40 + 20 - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 75 - true - - - - Mixer OK - - - - - - - - - - - - + + + Qt::Horizontal + + + + + + + 0 + + + + true + + + false + + - + - + - + + + + 0 + 0 + + 75 @@ -605,19 +124,15 @@ margin:1px; - Frame type: + Airplane type: - - - Select the Multirotor frame type here. - - + - + Qt::Horizontal @@ -632,13 +147,478 @@ margin:1px; - + + + + - + + + + 0 + 0 + + + + + 230 + 100 + + + + Output Channel Assignments + + + + + + Engine + + + + + + + Select output channel for the engine + + + + + + + + 60 + 0 + + + + Aileron 1 + + + + + + + Select output channel for the first aileron (or elevon) + + + + + + + false + + + + 60 + 0 + + + + Aileron 2 + + + + + + + false + + + Select output channel for the second aileron (or elevon) + + + + + + + + 67 + 0 + + + + Elevator 1 + + + + + + + Select output channel for the first elevator + + + + + + + false + + + + 67 + 0 + + + + Elevator 2 + + + + + + + false + + + Select output channel for a secondary elevator + + + + + + + Rudder 1 + + + + + + + Select output channel for the first rudder + + + + + + + Rudder 2 + + + + + + + Select output channel for a secondary rudder + + + + + + + Qt::Vertical + + + + 20 + 20 + + + + + + + + + + + + 0 + 0 + + + + Elevon Mix + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 0 + 20 + + + + + + + + + + + + + 65 + 0 + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Rudder % + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + 50 + + + Qt::AlignCenter + + + + + + + + + + + + 50 + 0 + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Pitch % + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + 50 + + + Qt::AlignCenter + + + + + + + + + + + + + + Qt::Horizontal + + + + 20 + 20 + + + + + + + + + 0 + 100 + + + + Throttle Curve + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 20 + + + + + + + + + 0 + 0 + + + + + 100 + 100 + + + + + 200 + 200 + + + + + 10 + 10 + + + + + + + + + 200 + 16777215 + + + + Reset + + + + + + + Val: 0.00 + + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 75 + true + + + + Mixer OK + + + + + + + + + + + + + + + + + - + - + 75 @@ -646,12 +626,19 @@ margin:1px; - Mix Level + Frame type: - + + + Select the Multirotor frame type here. + + + + + Qt::Horizontal @@ -666,322 +653,702 @@ margin:1px; - + - + - - - - 30 - 0 - - - - 100 - - - Qt::AlignCenter - - + + + + + + 75 + true + + + + Mix Level + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + - - - - 35 - 0 - - - - Weight of Roll mixing in percent. + + + + + + + + 30 + 0 + + + + 100 + + + Qt::AlignCenter + + + + + + + + 35 + 0 + + + + Weight of Roll mixing in percent. Typical values are 100% for + configuration and 50% for X configuration on quads. - - - 100 - - - 100 - - - Qt::Vertical - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + 100 + + + 100 + + + Qt::Vertical + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - R - - - Qt::AlignCenter - - - - - - - - - - - - 0 - 0 - - - - 100 - - - Qt::AlignCenter - - - - - - - - 35 - 0 - - - - Weight of Pitch mixing in percent. + + + R + + + Qt::AlignCenter + + + + + + + + + + + + 0 + 0 + + + + 100 + + + Qt::AlignCenter + + + + + + + + 35 + 0 + + + + Weight of Pitch mixing in percent. Typical values are 100% for + configuration and 50% for X configuration on quads. - - - 100 - - - 100 - - - Qt::Vertical - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + 100 + + + 100 + + + Qt::Vertical + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - P - - - Qt::AlignCenter - - - - - - - - - - - - 0 - 0 - - - - 50 - - - Qt::AlignCenter - - - - - - - - 40 - 0 - - - - Weight of Yaw mixing in percent. + + + P + + + Qt::AlignCenter + + + + + + + + + + + + 0 + 0 + + + + 50 + + + Qt::AlignCenter + + + + + + + + 40 + 0 + + + + Weight of Yaw mixing in percent. Typical value is 50% for + or X configuration on quads. - - - -100 - - - 100 - - - 50 - - - Qt::Vertical - - - - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + -100 + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - Y - - - Qt::AlignCenter - - + + + Y + + + Qt::AlignCenter + + + + + + + + + + + 0 + 0 + + + + + 110 + 110 + + + + background:transparent + + + QFrame::NoFrame + + + QFrame::Plain + + + - - - - 0 - 0 - + + + Qt::Horizontal - + - 110 - 110 + 40 + 20 - - background:transparent - - - QFrame::NoFrame - - - QFrame::Plain + + + + + + Throtte Curve + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 10 + + + + + + + + + 0 + 0 + + + + + 120 + 120 + + + + background:transparent + + + + + + + + 0 + 0 + + + + + 200 + 16777215 + + + + Reset + + + + + + + Val: 0.00 + + + + - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Throtte Curve - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - - - - - 0 - 0 - - - - - 120 - 120 - - - - background:transparent - - - - - - - - 0 - 0 - - - - - 200 - 16777215 - - - - Reset - - - - - - - Val: 0.00 - - - - - - - - - - - - 10 - - - - + + + 10 + - + + + + + + + + 75 + true + + + + Tricopter Yaw + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + channel: + + + + + + + false + + + + 0 + 0 + + + + + 40 + 0 + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + Motor output channels + + + + 1 + + + 1 + + + + + QFormLayout::AllNonFixedFieldsGrow + + + 3 + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 1 + + + + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 2 + + + + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 3 + + + + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 4 + + + + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 0 + 20 + + + + + + + + + + QFormLayout::AllNonFixedFieldsGrow + + + 3 + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 5 + + + + + + + false + + + + 0 + 0 + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 6 + + + + + + + false + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 7 + + + + + + + false + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 8 + + + + + + + false + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 20 + + + + + + + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + 75 @@ -989,12 +1356,72 @@ margin:1px; - Tricopter Yaw + Mixer OK + + + + + + + + + + + + + 0 + + + 0 + + + + + 0 + + + + + + + + + + + true + + + false + + + + + + + + + + + 0 + 0 + + + + + 75 + true + + + + Vehicle type: - + + + + Qt::Horizontal @@ -1009,40 +1436,425 @@ margin:1px; - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - channel: - - + + + + + + 75 + true + + + + Channel Assignment + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + - - - false - - - - 0 - 0 - - - - - 40 - 0 - - - + + + + + + 0 + 0 + + + + + 0 + 100 + + + + Output channel asignmets + + + + + + + 77 + 0 + + + + Engine + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Select output channel for the engine + + + + + + + + 60 + 0 + + + + Aileron 1 + + + + + + + Select output channel for the first aileron (or elevon) + + + + + + + false + + + + 60 + 0 + + + + Aileron 2 + + + + + + + false + + + Select output channel for the second aileron (or elevon) + + + + + + + + 0 + 0 + + + + Motor + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Select output channel for the first motor + + + + + + + false + + + + 47 + 0 + + + + Motor 2 + + + + + + + false + + + Select output channel for a second motor + + + + + + + Front Steering + + + + + + + Select output channel for the first steering actuator + + + + + + + Rear Steering + + + + + + + Select output channel for a second steering actuator + + + + + + + + + + true + + + + 0 + 0 + + + + Differential Steering Mix + + + + + + + + + + + 65 + 0 + + + + Left % + + + + + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + 50 + + + + + + + + + + + + 50 + 0 + + + + Right % + + + + + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + 50 + + + + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 100 + + + + Front throttle curve + + + + + + + 0 + 0 + + + + + 100 + 100 + + + + + 200 + 200 + + + + + 10 + 10 + + + + + + + + + 200 + 16777215 + + + + Reset + + + + + + + Val: 0.00 + + + + + + + + + + Rear throttle curve + + + + + + + 0 + 0 + + + + + 100 + 100 + + + + + 200 + 200 + + + + + + + + Reset + + + + + + + Val: 0.00 + + + + + + + - + Qt::Vertical @@ -1054,1428 +1866,641 @@ margin:1px; + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 75 + true + + + + Mixer OK + + + + + - - - - Motor output channels - - - - 1 - - - 1 - - - - - QFormLayout::AllNonFixedFieldsGrow - - - 3 - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 1 - - - - - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 2 - - - - - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 3 - - - - - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 4 - - - - - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 0 - 20 - - - - - - - - - - QFormLayout::AllNonFixedFieldsGrow - - - 3 - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 5 - - - - - - - false - - - - 0 - 0 - - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 6 - - - - - - - false - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 7 - - - - - - - false - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 8 - - - - - - - false - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 20 - - - - - - - - - - - - + + + - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 75 - true - - - - Mixer OK - - - - - - - - - - - - - 0 - - - 0 - - - - - 0 - - - - - - - - - - - true - - - false - - - - - - - - - - - 0 - 0 - - - - - 75 - true - - - - Vehicle type: - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - - 75 - true - - - - Channel Assignment - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - - 0 - 0 - - - - - 0 - 100 - - - - Output channel asignmets - - - - - - - 77 - 0 - - - - Engine - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Select output channel for the engine - - - - - - - - 60 - 0 - - - - Aileron 1 - - - - - - - Select output channel for the first aileron (or elevon) - - - - - - - false - - - - 60 - 0 - - - - Aileron 2 - - - - - - - false - - - Select output channel for the second aileron (or elevon) - - - - - - - - 0 - 0 - - - - Motor - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Select output channel for the first motor - - - - - - - false - - - - 47 - 0 - - - - Motor 2 - - - - - - - false - - - Select output channel for a second motor - - - - - - - Front Steering - - - - - - - Select output channel for the first steering actuator - - - - - - - Rear Steering - - - - - - - Select output channel for a second steering actuator - - - - - - - - - - true - - - - 0 - 0 - - - - Differential Steering Mix - - - - - - + + + + + + + Curve 1 + + - + + + + 0 + 0 + + - 65 + 100 + 100 + + + + + 200 + 200 + + + + + + + + + 0 + 0 + + + + + 0 0 - Left % + Reset - - - 100 - - - 50 - - - Qt::Vertical - - - - - + - 50 + Val: 0.00 - - - + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Curve 2 + + - + + + + 0 + 0 + + - 50 - 0 + 100 + 100 - - Right % + + + 200 + 200 + - - - 100 - - - 50 - - - Qt::Vertical + + + Reset - + - 50 + Val: 0.00 - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 100 - - - - Front throttle curve - - - - - - - 0 - 0 - - - - - 100 - 100 - - - - - 200 - 200 - - - - - 10 - 10 - - - - - - - - - 200 - 16777215 - - + + + + + + + + + 0 + 0 + + + + true + + + 50 + + + false + + - Reset + Type - - - - + + - Val: 0.00 + Curve 1 - - - - - - - - - Rear throttle curve - - - - - - - 0 - 0 - - - - - 100 - 100 - - - - - 200 - 200 - - - - - - + + - Reset + Curve 2 - - - - + + - Val: 0.00 + Roll - - - - + + + + Pitch + + + + + Yaw + + + + + Ch 1 + + + + + Ch 2 + + + + + Ch 3 + + + + + Ch 4 + + + + + Ch 5 + + + + + Ch 6 + + + + + Ch 7 + + + + + Ch 8 + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 75 - true - - - - Mixer OK - - - - - - - - - - - - - - - - - - - Curve 1 - - - - - - - 0 - 0 - - - - - 100 - 100 - - - - - 200 - 200 - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - Reset - - - - - - - Val: 0.00 - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Curve 2 - - - - - - - 0 - 0 - - - - - 100 - 100 - - - - - 200 - 200 - - - - - - - - Reset - - - - - - - Val: 0.00 - - - - - - - - - - - - - 0 - 0 - - - - true - - - 50 - - - false - - - - Type - - - - - Curve 1 - - - - - Curve 2 - - - - - Roll - - - - - Pitch - - - - - Yaw - - - - - Ch 1 - - - - - Ch 2 - - - - - Ch 3 - - - - - Ch 4 - - - - - Ch 5 - - - - - Ch 6 - - - - - Ch 7 - - - - - Ch 8 - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - + + @@ -2487,301 +2512,328 @@ margin:1px; Advanced Settings - + + + 12 + + + 12 + + + 12 + - - - + + + QFrame::NoFrame + + + true + + + + + 0 + 0 + 249 + 303 + + + - - - - 75 - true - - - - Feed Forward - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - QFormLayout::AllNonFixedFieldsGrow - - - + - - - FeedForward - - + + + + + + 75 + true + + + + Feed Forward + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + - - - - 30 - 0 - + + + QFormLayout::AllNonFixedFieldsGrow - - 000 - - - - - - - - - true - - - Qt::StrongFocus - - - Overall level of feed forward (in percentage). - - - 100 - - - 1 - - - Qt::Horizontal - - - QSlider::NoTicks - - - - - - - Accel Time Constant - - - - - - - true - - - Qt::StrongFocus - - - In miliseconds. + + + + + + FeedForward + + + + + + + + 30 + 0 + + + + 000 + + + + + + + + + true + + + Qt::StrongFocus + + + Overall level of feed forward (in percentage). + + + 100 + + + 1 + + + Qt::Horizontal + + + QSlider::NoTicks + + + + + + + Accel Time Constant + + + + + + + true + + + Qt::StrongFocus + + + In miliseconds. When tuning: Slowly raise accel time from zero to just under the level where the motor starts to overshoot its target speed. - - - 3 - - - 100.000000000000000 - - - 0.010000000000000 - - - - - - - Decel Time Constant - - - - - - - true - - - Qt::StrongFocus - - - When tuning: Slowly raise decel time from zero to just + + + 3 + + + 100.000000000000000 + + + 0.010000000000000 + + + + + + + Decel Time Constant + + + + + + + true + + + Qt::StrongFocus + + + When tuning: Slowly raise decel time from zero to just under the level where the motor starts to undershoot its target speed when decelerating. Do it after accel time is setup. - - - 3 - - - 100.000000000000000 - - - 0.010000000000000 - - - - - - - - - MaxAccel - - - - - - - 1000 - - - - - - - - - Qt::StrongFocus - - - Limits how much the engines can accelerate or decelerate. + + + 3 + + + 100.000000000000000 + + + 0.010000000000000 + + + + + + + + + MaxAccel + + + + + + + 1000 + + + + + + + + + Qt::StrongFocus + + + Limits how much the engines can accelerate or decelerate. In 'units per second', a sound default is 1000. - - - 500 - - - 2000 - - - 1000 - - - Qt::Horizontal - - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::StrongFocus - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + + + 500 + + + 2000 + + + 1000 + + + Qt::Horizontal + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::StrongFocus + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } </style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html> - - - - - - - - - - Qt::StrongFocus - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + + + + + + + + + + Qt::StrongFocus + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } </style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html> - - - - - - - - - - Qt::StrongFocus - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + + + + + + + + + + Qt::StrongFocus + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } </style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html> - - - Enable FF tuning - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - 0 - 0 - - - - - 0 - 40 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + + + Enable FF tuning + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + 0 + 0 + + + + + 0 + 40 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } </style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;"> @@ -2789,99 +2841,166 @@ p, li { white-space: pre-wrap; } <tr> <td style="border: none;"> <p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD IS DANGEROUS</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</p> <p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</p></td></tr></table></body></html> - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 32 - 32 - - - - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 32 - 32 - - - - true - - - - - - - Send to board, but don't save permanently (flash or SD). - - - Apply - - - - - - - Applies and Saves all settings to flash or SD depending on board. - - - Save - - - - + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 32 + 32 + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + true + + + + + + + + 60 + 28 + + + + Send to board, but don't save permanently (flash or SD). + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Apply + + + + + + + + 60 + 28 + + + + Applies and Saves all settings to flash or SD depending on board. + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Save + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index e535faa50..f935b6dcb 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -6,640 +6,707 @@ 0 0 - 720 - 739 + 820 + 845 Form - + + + 12 + - - - QFrame::NoFrame + + + 0 - - true + + Qt::ElideMiddle - - - - 0 - 0 - 696 - 635 - - - + + + Camera Stabilization + + + + 12 + + + 12 + + + 12 + + + 12 + - - - Qt::StrongFocus + + + false - - Enable CameraStabilization module + + QFrame::NoFrame - - - - - - After enabling the module, you must power cycle before using and configuring. + + QFrame::Plain - - - - - - Qt::Horizontal + + true - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 100 - - - - Basic Settings (Stabilization) - - - - - - Qt::StrongFocus - - - Camera yaw angle for 100% output value, deg. + + + + 0 + 0 + 766 + 622 + + + + true + + + + 12 + + + + + + 0 + 0 + + + + + 0 + 88 + + + + + + + + + + Qt::StrongFocus + + + Enable CameraStabilization module + + + + + + + After enabling the module, you must power cycle before using and configuring. + + + + + + + + + + + 0 + 0 + + + + + 0 + 131 + + + + Basic Settings (Stabilization) + + + false + + + + + + Qt::StrongFocus + + + Camera yaw angle for 100% output value, deg. This value should be tuned for particular gimbal and servo. You also have to define channel output range using Output configuration tab. - - - 180 - - - 20 - - - - - - - Qt::StrongFocus - - - Camera pitch angle for 100% output value, deg. + + + 180 + + + 20 + + + + + + + Qt::StrongFocus + + + Camera pitch angle for 100% output value, deg. This value should be tuned for particular gimbal and servo. You also have to define channel output range using Output configuration tab. - - - 180 - - - 20 - - - - - - - Qt::StrongFocus - - - Camera roll angle for 100% output value, deg. + + + 180 + + + 20 + + + + + + + Qt::StrongFocus + + + Camera roll angle for 100% output value, deg. This value should be tuned for particular gimbal and servo. You also have to define channel output range using Output configuration tab. - - - 180 - - - 20 - - - - - - - Qt::StrongFocus - - - Yaw output channel for camera gimbal - - - - None + + + 180 + + + 20 + + + + + + + Qt::StrongFocus + + + Yaw output channel for camera gimbal + + + + None + + + + + + + + Qt::StrongFocus + + + Pitch output channel for camera gimbal + + + + None + + + + + + + + Qt::StrongFocus + + + Roll output channel for camera gimbal + + + + None + + + + + + + + Output Channel + + + + + + + Output Range + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Yaw + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Pitch + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Roll + + + Qt::AlignCenter + + + + + + + + + + true - - - - - - - Qt::StrongFocus - - - Pitch output channel for camera gimbal - - - - None + + Qt::Horizontal - - - - - - - Qt::StrongFocus - - - Roll output channel for camera gimbal - - - - None + + + + + + Qt::Vertical - - - - - - - Output Channel - - - - - - - Output Range - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + QSizePolicy::Preferred + + + + 20 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 266 + + + + Advanced Settings (Control) + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - Yaw - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + Yaw + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - Pitch - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + Pitch + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - Roll - - - Qt::AlignCenter - - - - - - - - - - - 0 - 0 - - - - - 0 - 204 - - - - Advanced Settings (Control) - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Yaw - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Pitch - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Roll - - - Qt::AlignCenter - - - - - - - Qt::StrongFocus - - - Input channel to control camera yaw + + + Roll + + + Qt::AlignCenter + + + + + + + Qt::StrongFocus + + + Input channel to control camera yaw Don't forget to map this channel using Input configuration tab. - - - - None - - - - - - - - Qt::StrongFocus - - - Input channel to control camera pitch + + + + None + + + + + + + + Qt::StrongFocus + + + Input channel to control camera pitch Don't forget to map this channel using Input configuration tab. - - - - None - - - - - - - - Qt::StrongFocus - - - Input channel to control camera roll + + + + None + + + + + + + + Qt::StrongFocus + + + Input channel to control camera roll Don't forget to map this channel using Input configuration tab. - - - - None - - - - - - - - Input Channel - - - - - - - Qt::StrongFocus - - - Axis stabilization mode + + + + None + + + + + + + + Input Channel + + + + + + + Qt::StrongFocus + + + Axis stabilization mode Attitude: camera tracks level for the axis. Input controls the deflection. AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. - - - - Attitude - - - - - - - - Qt::StrongFocus - - - Maximum camera yaw deflection for 100% input in Attitude mode, deg. - - - 180 - - - 20 - - - - - - - Qt::StrongFocus - - - Maximum camera yaw rate for 100% input in AxisLock mode, deg/s. - - - 180 - - - 50 - - - - - - - Qt::StrongFocus - - - Input low-pass filter response time for yaw axis, ms. + + + + Attitude + + + + + + + + Qt::StrongFocus + + + Maximum camera yaw deflection for 100% input in Attitude mode, deg. + + + 180 + + + 20 + + + + + + + Qt::StrongFocus + + + Maximum camera yaw rate for 100% input in AxisLock mode, deg/s. + + + 180 + + + 50 + + + + + + + Qt::StrongFocus + + + Input low-pass filter response time for yaw axis, ms. This option smoothes the stick input. Zero value disables LPF. - - - 1000 - - - 150 - - - - - - - Qt::StrongFocus - - - Axis stabilization mode + + + 1000 + + + 150 + + + + + + + Qt::StrongFocus + + + Axis stabilization mode Attitude: camera tracks level for the axis. Input controls the deflection. AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. - - - - Attitude - - - - - - - - Qt::StrongFocus - - - Maximum camera pitch deflection for 100% input in Attitude mode, deg. - - - 180 - - - 20 - - - - - - - Qt::StrongFocus - - - Maximum camera pitch rate for 100% input in AxisLock mode, deg/s. - - - 180 - - - 50 - - - - - - - Qt::StrongFocus - - - Input low-pass filter response time for pitch axis, ms. + + + + Attitude + + + + + + + + Qt::StrongFocus + + + Maximum camera pitch deflection for 100% input in Attitude mode, deg. + + + 180 + + + 20 + + + + + + + Qt::StrongFocus + + + Maximum camera pitch rate for 100% input in AxisLock mode, deg/s. + + + 180 + + + 50 + + + + + + + Qt::StrongFocus + + + Input low-pass filter response time for pitch axis, ms. This option smoothes the stick input. Zero value disables LPF. - - - 1000 - - - 150 - - - - - - - Qt::StrongFocus - - - Axis stabilization mode + + + 1000 + + + 150 + + + + + + + Qt::StrongFocus + + + Axis stabilization mode Attitude: camera tracks level for the axis. Input controls the deflection. AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. - - - - Attitude - - - - - - - - Qt::StrongFocus - - - Maximum camera roll deflection for 100% input in Attitude mode, deg. - - - 180 - - - 20 - - - - - - - Qt::StrongFocus - - - Maximum camera roll rate for 100% input in AxisLock mode, deg/s. - - - 180 - - - 50 - - - - - - - Qt::StrongFocus - - - Input low-pass filter response time for roll axis, ms. + + + + Attitude + + + + + + + + Qt::StrongFocus + + + Maximum camera roll deflection for 100% input in Attitude mode, deg. + + + 180 + + + 20 + + + + + + + Qt::StrongFocus + + + Maximum camera roll rate for 100% input in AxisLock mode, deg/s. + + + 180 + + + 50 + + + + + + + Qt::StrongFocus + + + Input low-pass filter response time for roll axis, ms. This option smoothes the stick input. Zero value disables LPF. - - - 1000 - - - 150 - - - - - - - MaxAxisLockRate - - - - - - - Response Time - - - - - - - Input Rate - - - - - - - Input Range - - - - - - - Stabilization Mode - - - - - - - (the same value for Roll, Pitch, Yaw) - - - - - - - Qt::StrongFocus - - - Stick input deadband for all axes in AxisLock mode, deg/s. + + + 1000 + + + 150 + + + + + + + MaxAxisLockRate + + + + + + + Response Time + + + + + + + Input Rate + + + + + + + Input Range + + + + + + + Stabilization Mode + + + + + + + (the same value for Roll, Pitch, Yaw) + + + + + + + Qt::StrongFocus + + + Stick input deadband for all axes in AxisLock mode, deg/s. When stick input is within the MaxAxisLockRate range, camera tracks current attitude. Otherwise it starts moving according to input with @@ -647,159 +714,261 @@ rate depending on input value. If you have drift in your Tx controls, you may want to increase this value. - - - 1 - - - 0.100000000000000 - - - 1.000000000000000 - - - - + + + 1 + + + 0.100000000000000 + + + 1.000000000000000 + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - - - - - - QFrame::StyledPanel - - - QFrame::Raised - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 32 - 32 - - - - - true - - - - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 32 - 32 - - - - Ctrl+S - - - false - - - true - - - - - - - Load default CameraStabilization settings except output channels + + + Messages + + + + + + + + + + + + + + + + + + + + + + + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 32 + 32 + + + + + true + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + Ctrl+S + + + false + + + true + + + + + + + + 130 + 28 + + + + Load default CameraStabilization settings except output channels Loaded settings are not applied automatically. You have to click the Apply or Save button afterwards. - - - Reset To Defaults - - - - - - - Send settings to the board but do not save to the non-volatile memory - - - Apply - - - - - - - Send settings to the board and save to the non-volatile memory - - - Save - - - false - - - - - - + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Reset To Defaults + + + + + + + + 60 + 28 + + + + Send settings to the board but do not save to the non-volatile memory + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Apply + + + + + + + + 60 + 28 + + + + Send settings to the board and save to the non-volatile memory + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Save + + + false + + + + + + + + + - enableCameraStabilization rollChannel pitchChannel yawChannel diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 331c39e23..89d866274 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -48,7 +48,7 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa autoLoadWidgets(); realtimeUpdates=new QTimer(this); connect(m_stabilization->realTimeUpdates_6,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int))); - connect(m_stabilization->realTimeUpdates_7,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int))); + //connect(m_stabilization->realTimeUpdates_7,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int))); connect(realtimeUpdates,SIGNAL(timeout()),this,SLOT(apply())); connect(m_stabilization->checkBox_7,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); @@ -66,8 +66,8 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa m_stabilization->saveStabilizationToRAM_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); m_stabilization->saveStabilizationToSD_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); m_stabilization->stabilizationReloadBoardData_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->saveStabilizationToRAM_7->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->saveStabilizationToSD_7->setAttribute(Qt::WA_LayoutUsesWidgetRect); + // m_stabilization->saveStabilizationToRAM_7->setAttribute(Qt::WA_LayoutUsesWidgetRect); + // m_stabilization->saveStabilizationToSD_7->setAttribute(Qt::WA_LayoutUsesWidgetRect); m_stabilization->pushButton_2->setAttribute(Qt::WA_LayoutUsesWidgetRect); m_stabilization->pushButton_3->setAttribute(Qt::WA_LayoutUsesWidgetRect); m_stabilization->pushButton_4->setAttribute(Qt::WA_LayoutUsesWidgetRect); @@ -88,7 +88,7 @@ ConfigStabilizationWidget::~ConfigStabilizationWidget() void ConfigStabilizationWidget::realtimeUpdatesSlot(int value) { m_stabilization->realTimeUpdates_6->setCheckState((Qt::CheckState)value); - m_stabilization->realTimeUpdates_7->setCheckState((Qt::CheckState)value); + //m_stabilization->realTimeUpdates_7->setCheckState((Qt::CheckState)value); if(value==Qt::Checked && !realtimeUpdates->isActive()) realtimeUpdates->start(300); else if(value==Qt::Unchecked) diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index e00f4baf3..561e0fe9f 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -6,77 +6,806 @@ 0 0 - 626 - 532 + 692 + 958 Form - + + + 12 + - 1 + 0 RC Input - - - - - 0 + + + 12 + + + 12 + + + 12 + + + + + QFrame::NoFrame - - - - + + true + + + + + 0 + 0 + 638 + 801 + + + + + + + 0 + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Preferred + + + + 20 + 5 + + + + + + + + + + Roll/Pitch/Yaw stick deadband + + + + + + + Stick deadband in percents of full range (0-10), zero to disable + + + 1 + + + 10.000000000000000 + + + 0.100000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Preferred + + + + 20 + 5 + + + + + + + + Start Configuration Wizard + + + + + + + Run Calibration + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + 0 + 0 + + + + + 0 + 90 + + + + TextLabel + + + true + + + + + + + + + + + + + + + + + + + Back + + + + + + + Next + + + + + + + Cancel + + + + + + + + + + + + + + + + + Flight Mode Switch Settings + + + + 12 + + + 12 + + + 12 + + + + + QFrame::NoFrame + + + true + + + + + 0 + 0 + 100 + 30 + + + + + + 10 + 310 + 611 + 151 + + + + + + + Configure each stabilization mode for each axis + + + + + + Stabilized3 + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Roll + + + Qt::AlignCenter + + + + + + + + 102 + 0 + + + + Qt::StrongFocus + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Pitch + + + Qt::AlignCenter + + + + + + + Qt::StrongFocus + + + + + + + Qt::StrongFocus + + + + + + + Qt::StrongFocus + + + + + + + Stabilized1 + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Yaw + + + Qt::AlignCenter + + + + + + + Qt::StrongFocus + + + + + + + + 102 + 0 + + + + Qt::StrongFocus + + + + + + + Qt::StrongFocus + + + + + + + Qt::StrongFocus + + + + + + + Stabilized2 + + + Qt::AlignCenter + + + + + + + + 102 + 0 + + + + Qt::StrongFocus + + + + + + + + + 10 + 20 + 611 + 231 + + + + FlightMode Switch Positions + + + + false + + + + 100 + 140 + 151 + 26 + + + + Qt::StrongFocus + + + + + false + + + + 100 + 110 + 151 + 26 + + + + Qt::StrongFocus + + + Select the stabilization mode on this position (manual/stabilized/auto) + + + + + + 10 + 115 + 62 + 17 + + + + Pos. 4 + + + + + false + + + + 100 + 170 + 151 + 26 + + + + Qt::StrongFocus + + + + + + 10 + 145 + 62 + 17 + + + + Pos. 5 + + + + + + 10 + 175 + 62 + 17 + + + + Pos. 6 + + + + + false + + + + 70 + 28 + 20 + 160 + + + + Qt::StrongFocus + + + This slider moves when you move the flight mode switch +on your remote. It shows currently active flight mode. + +Setup the flight mode channel on the RC Input tab if you have not done so already. + + + 0 + + + 5 + + + 10 + + + 0 + + + 0 + + + Qt::Vertical + + + true + + + QSlider::TicksBelow + + + 1 + + + + + + 100 + 50 + 151 + 26 + + + + Qt::StrongFocus + + + + + + 100 + 80 + 151 + 26 + + + + Qt::StrongFocus + + + + + + 100 + 20 + 151 + 26 + + + + Qt::StrongFocus + + + Select the stabilization mode on this position (manual/stabilized/auto) + + + + + + 11 + 55 + 62 + 17 + + + + Pos. 2 + + + + + + 11 + 25 + 62 + 17 + + + + Pos. 1 + + + + + + 11 + 85 + 62 + 17 + + + + Pos. 3 + + + + + + 458 + 20 + 61 + 20 + + + + Number of positions your FlightMode switch has. + +Default is 3. + +It will be 2 or 3 for most of setups, but it also can be up to 6. +In that case you have to configure your radio mixers so the whole range +from min to max is split into N equal intervals, and you may set arbitrary +channel value for each flight mode. + + + 1 + + + 6 + + + 3 + + + + + + 277 + 22 + 171 + 16 + + + + Number of flight modes: + + + + + + 310 + 120 + 191 + 30 + + + + + 75 + true + + + + Avoid "Manual" for multirotors! + + + true + + + + + + + + + + + Arming Settings + + + + 12 + + + 12 + + + 12 + + + + + QFrame::NoFrame + + + true + + + + + 0 + 0 + 499 + 121 + + + - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 5 - - - - - - - - + + + + + + 50 + false + + - Roll/Pitch/Yaw stick deadband + Arm airframe using throttle off and: - - + + + + Qt::StrongFocus + - Stick deadband in percents of full range (0-10), zero to disable - - - 1 - - - 10.000000000000000 - - - 0.100000000000000 + Indicate the control used for arming the airframe, in addition to setting the throttle to its minimum position. In other terms "Throttle Off". - - + + Qt::Horizontal @@ -91,795 +820,210 @@ - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 5 - - - + + + + + Arming timeout: + + + + + + + Qt::StrongFocus + + + After the time indicated here, the frame go back to disarmed state. + + + 64 + + + + + + + seconds. + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + - + - Start Configuration Wizard + Airframe disarm is done by throttle off and opposite of above combination. - - - Run Calibration - - - - - + Qt::Vertical 20 - 40 + 467 - - - - - - - 0 - 0 - - - - - 0 - 90 - - - - TextLabel - - - true - - - - - - - - - - - - - - - - - - - Back - - - - - - - Next - - - - - - - Cancel - - - - - - - - - - Flight Mode Switch Settings - - - - - 30 - 260 - 541 - 161 - - - - - - - Configure each stabilization mode for each axis - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Yaw - - - Qt::AlignCenter - - - - - - - Stabilized1 - - - Qt::AlignCenter - - - - - - - - 102 - 0 - - - - Qt::StrongFocus - - - - - - - - 102 - 0 - - - - Qt::StrongFocus - - - - - - - - 102 - 0 - - - - Qt::StrongFocus - - - - - - - Stabilized2 - - - Qt::AlignCenter - - - - - - - Qt::StrongFocus - - - - - - - Qt::StrongFocus - - - - - - - Qt::StrongFocus - - - - - - - Stabilized3 - - - Qt::AlignCenter - - - - - - - Qt::StrongFocus - - - - - - - Qt::StrongFocus - - - - - - - Qt::StrongFocus - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Roll - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Pitch - - - Qt::AlignCenter - - - - - - - Qt::Vertical - - - - 20 - 20 - - - - - - - - - - 30 - 20 - 541 - 211 - - - - FlightMode Switch Positions - - - - false - - - - 100 - 140 - 151 - 26 - - - - Qt::StrongFocus - - - - - false - - - - 100 - 110 - 151 - 26 - - - - Qt::StrongFocus - - - Select the stabilization mode on this position (manual/stabilized/auto) - - - - - - 10 - 115 - 62 - 17 - - - - Pos. 4 - - - - - false - - - - 100 - 170 - 151 - 26 - - - - Qt::StrongFocus - - - - - - 10 - 145 - 62 - 17 - - - - Pos. 5 - - - - - - 10 - 175 - 62 - 17 - - - - Pos. 6 - - - - - false - - - - 70 - 28 - 20 - 160 - - - - Qt::StrongFocus - - - This slider moves when you move the flight mode switch -on your remote. It shows currently active flight mode. - -Setup the flight mode channel on the RC Input tab if you have not done so already. - - - 0 - - - 5 - - - 10 - - - 0 - - - 0 - - - Qt::Vertical - - - true - - - QSlider::TicksBelow - - - 1 - - - - - - 100 - 50 - 151 - 26 - - - - Qt::StrongFocus - - - - - - 100 - 80 - 151 - 26 - - - - Qt::StrongFocus - - - - - - 100 - 20 - 151 - 26 - - - - Qt::StrongFocus - - - Select the stabilization mode on this position (manual/stabilized/auto) - - - - - - 11 - 55 - 62 - 17 - - - - Pos. 2 - - - - - - 11 - 25 - 62 - 17 - - - - Pos. 1 - - - - - - 11 - 85 - 62 - 17 - - - - Pos. 3 - - - - - - 458 - 20 - 61 - 20 - - - - Number of positions your FlightMode switch has. - -Default is 3. - -It will be 2 or 3 for most of setups, but it also can be up to 6. -In that case you have to configure your radio mixers so the whole range -from min to max is split into N equal intervals, and you may set arbitrary -channel value for each flight mode. - - - 1 - - - 6 - - - 3 - - - - - - 277 - 22 - 171 - 16 - - - - Number of flight modes: - - - - - - 310 - 120 - 191 - 30 - - - - - 75 - true - - - - Avoid "Manual" for multirotors! - - - true - - - - groupBox_2 - groupBox - - - - Arming Settings - - - - - - - - - 50 - false - - - - Arm airframe using throttle off and: - - - - - - - Qt::StrongFocus - - - Indicate the control used for arming the airframe, in addition to setting the throttle to its minimum position. In other terms "Throttle Off". - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - Arming timeout: - - - - - - - Qt::StrongFocus - - - After the time indicated here, the frame go back to disarmed state. - - - 64 - - - - - - - seconds. - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Airframe disarm is done by throttle off and opposite of above combination. - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 32 - 32 - - - - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 32 - 32 - - - - true - - - - - - - Send to OpenPilot but don't write in SD. + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 32 + 32 + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + true + + + + + + + + 60 + 28 + + + + Send to OpenPilot but don't write in SD. Be sure to set the Neutral position on all sliders before sending! - - - Apply - - - - - - - Be sure to set the Neutral position on all sliders before sending! + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Apply + + + + + + + + 60 + 28 + + + + Be sure to set the Neutral position on all sliders before sending! Applies and Saves all settings to SD - - - Save - - - - + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Save + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.ui b/ground/openpilotgcs/src/plugins/config/inputchannelform.ui index a32599c30..d78727f9a 100644 --- a/ground/openpilotgcs/src/plugins/config/inputchannelform.ui +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.ui @@ -7,7 +7,7 @@ 0 0 767 - 58 + 59 @@ -166,7 +166,7 @@ font:bold; - 0 + 45 26 diff --git a/ground/openpilotgcs/src/plugins/config/output.ui b/ground/openpilotgcs/src/plugins/config/output.ui index de87ef7eb..b2e8c9ca2 100644 --- a/ground/openpilotgcs/src/plugins/config/output.ui +++ b/ground/openpilotgcs/src/plugins/config/output.ui @@ -6,475 +6,650 @@ 0 0 - 659 - 523 + 664 + 791 Form - + + + 12 + - - - QFrame::StyledPanel + + + QTabWidget::Rounded - - QFrame::Raised + + 0 - - - 1 - - - 1 - - - 1 - - - 3 - - - 2 - - - - - - - Qt::Horizontal - - - QSizePolicy::Minimum - - - - 40 - 20 - - - - - - - - - 75 - true - - - - Channel: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + Qt::ElideMiddle + + + + Output + + + + 12 + + + 12 + + + 12 + + + + + QFrame::NoFrame + + + true + + + + + 0 + 0 + 610 + 634 + + + + + + + + + + + + Qt::Horizontal + + + QSizePolicy::Minimum + + + + 25 + 20 + + + + + + + + + 75 + true + + + + Channel: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + - + + + Qt::AlignCenter + + + + + + + - + + + Qt::AlignCenter + + + + + + + - + + + Qt::AlignCenter + + + + + + + - + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 20 + + + + Qt::Horizontal + + + QSizePolicy::Minimum + + + + 25 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 20 + + + + + 75 + true + + + + Update rate: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + false + + + + 0 + 0 + + + + + 0 + 20 + + + + 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 + + + + 0 + 0 + + + + + 0 + 20 + + + + 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 + + + + 0 + 0 + + + + + 0 + 20 + + + + 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 + + + + 0 + 0 + + + + + 0 + 20 + + + + Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. +Leave at 50Hz for fixed wing. + + + + 50 + + + + + 60 + + + + + 125 + + + + + 165 + + + + + 270 + + + + + 330 + + + + + 400 + + + + + + + + + + + 0 + + + QLayout::SetNoConstraint + + + + + + + + + + 519 + 0 + + + + Motors spin at neutral output when armed and throttle below zero (be careful) + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + Qt::Vertical + + + + 20 + 458 + + + + + - - - - - - - - - Qt::Horizontal - - - QSizePolicy::Minimum - - - - 40 - 20 - - - - - - - - - 75 - true - - - - Update rate: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - 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 - - - - + + + + - - - - - - Qt::Vertical + + + - - - 20 - 40 - - - - - - - - - - Motors spin at neutral output when armed and throttle below zero (be careful) - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - true - - - Move the servos using the sliders. Two important things: + + + + + + + true + + + + 105 + 0 + + + + Move the servos using the sliders. Two important things: - Take extra care if the output is connected to an motor controller! - Will only work if the RC receiver is working (failsafe) - - - Test outputs - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 32 - 32 - - - - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 32 - 32 - - - - true - - - - - - - Send to OpenPilot but don't write in SD. + + + Test outputs + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 32 + 32 + + + + + 32 + 32 + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + true + + + + + + + + 60 + 28 + + + + Send to OpenPilot but don't write in SD. Be sure to set the Neutral position on all sliders before sending! - - - Apply - - - - - - - Be sure to set the Neutral position on all sliders before sending! + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Apply + + + + + + + + 60 + 28 + + + + Be sure to set the Neutral position on all sliders before sending! Applies and Saves all settings to SD - - - Save - - - - + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Save + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 3f985a66e..b09ff05ca 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,8 +6,8 @@ 0 0 - 738 - 748 + 786 + 993 @@ -440,68 +440,86 @@ false - + + + 12 + + + 12 + - - - - - - 0 - 0 - + + + + 0 + 0 + + + + + 0 + 0 + + + + Qt::TabFocus + + + false + + + false + + + QTabWidget::North + + + QTabWidget::Rounded + + + 0 + + + false + + + false + + + + Basic + + + + 12 - - - 0 - 0 - - - - Qt::TabFocus - - - true - - - true - - - QTabWidget::North - - - 0 - - - true - - - - Basic - - - - - - QFrame::NoFrame + + + + QFrame::NoFrame + + + 0 + + + true + + + + + 0 + 0 + 732 + 832 + + + + + 12 - - 0 - - - true - - - - - 0 - 0 - 673 - 790 - - - - + + + Qt::Horizontal @@ -517,7 +535,7 @@ - + @@ -530,50 +548,41 @@ - - - - - 0 - 0 - - - - - 0 - 181 - - - - - 16777215 - 181 - - - - - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - + + + + + + + 0 + 0 + + + + + 0 + 181 + + + + + 16777215 + 181 + + + + + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + 4 + + @@ -592,7 +601,65 @@ - + + + + + 0 + 0 + + + + + 51 + 28 + + + + + 16777215 + 16777215 + + + + Takes you to the online wiki page for Rate settings + + + false + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Wiki + + + + button:help + url:http://wiki.openpilot.org/display/Doc/Stabilization+panel + + + + + @@ -612,6 +679,9 @@ 28 + + Reset all values to GCS defaults + false @@ -647,8 +717,3356 @@ border-radius: 4; - - + + + + + + + 0 + 0 + + + + + 0 + 131 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 50 + false + false + true + + + + false + + + + + + + + + true + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 78 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + + + + + + 100 + + + 51 + + + 51 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Kp + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Kp + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kp + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kp + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Kp + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + Slowly raise Proportional until you start seeing clear oscillations when you fly. +Then lower the value by 5 or so. + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Kp + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Ki + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Ki + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Ki + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Ki + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Ki + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Integral at roughly the same +value as the Kp. + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Ki + haslimits:yes + scale:0.0001 + buttongroup:1,10 + + + + + + + + + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 20 + 13 + + + + + + + + + 0 + 16 + + + + Attitude Stabilization (Outer Loop) + + + + + + + + + + 0 + 0 + + + + + 0 + 181 + + + + + 16777215 + 181 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + 4 + + + + + + 0 + 0 + + + + Qt::StrongFocus + + + + + + Link Roll and Pitch + + + + + 0 @@ -661,14 +4079,8 @@ border-radius: 4; 28 - - - 51 - 28 - - - - false + + Takes you to the online wiki page for Attitude settings QPushButton { @@ -702,3339 +4114,23 @@ border-radius: 4; - - - - - 0 - 0 - - - - - 0 - 131 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - Slowly raise Proportional until you start seeing clear oscillations when you fly. -Then lower the value by 5 or so. - - - - - - 100 - - - 51 - - - 51 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Kp - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - Slowly raise Proportional until you start seeing clear oscillations when you fly. -Then lower the value by 5 or so. - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Kp - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 3 - 22 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - Slowly raise Proportional until you start seeing clear oscillations when you fly. -Then lower the value by 5 or so. - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kp - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - Slowly raise Proportional until you start seeing clear oscillations when you fly. -Then lower the value by 5 or so. - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kp - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 3 - 22 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - Slowly raise Proportional until you start seeing clear oscillations when you fly. -Then lower the value by 5 or so. - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Kp - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - Slowly raise Proportional until you start seeing clear oscillations when you fly. -Then lower the value by 5 or so. - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Kp - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Integral at roughly the same -value as the Kp. - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Ki - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Integral at roughly the same -value as the Kp. - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Ki - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Integral at roughly the same -value as the Kp. - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Ki - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Integral at roughly the same -value as the Kp. - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Ki - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Integral at roughly the same -value as the Kp. - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Ki - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Integral at roughly the same -value as the Kp. - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Ki - haslimits:yes - scale:0.0001 - buttongroup:1,10 - - - - - - - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 20 - 13 - - - - - - - - - 0 - 16 - - - - Attitude Stabilization (Outer Loop) - - - - - - - - 0 - 0 - - - - - 0 - 181 - - - - - 16777215 - 181 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - Qt::StrongFocus - - - - - - Link Roll and Pitch - - - - + + + + 0 + 0 + + 81 28 + + Reset all values to GCS defaults + QPushButton { border: 1px outset #999; @@ -4067,2742 +4163,2697 @@ border-radius: 4; - - - - - 0 - 0 - - - - - 0 - 131 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 3 - 22 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 3 - 22 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 3 - 22 - - - - - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - - - - 51 - 28 - - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Wiki - - - - button:help - url:http://wiki.openpilot.org/display/Doc/Stabilization+panel - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - + + + + + + 0 + 0 + + + + + 0 + 131 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 78 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + Qt::Horizontal @@ -6818,7 +6869,7 @@ border-radius: 4; - + @@ -6831,571 +6882,587 @@ border-radius: 4; - - - - - 0 - 0 - - - - - 0 - 211 - - - - - 16777215 - 211 - - - - - - - + + + + + + + 0 + 0 + + + + + 0 + 211 + + + + + 16777215 + 211 + + + + + + + + + 0 + 0 + 0 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + - 255 - 255 - 255 + 250 + 250 + 250 - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + - 251 - 251 - 251 + 243 + 243 + 243 - - - - + + - 124 - 124 - 124 + 250 + 250 + 250 - - - - + + + + + + + + - 165 - 165 - 165 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + - 255 - 255 - 255 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - + + - 251 - 251 - 251 + 250 + 250 + 250 - - - - + + + + + + + + - 255 - 255 - 220 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + - 255 - 255 - 255 + 250 + 250 + 250 - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + - 251 - 251 - 251 + 243 + 243 + 243 - - - - + + - 124 - 124 - 124 + 250 + 250 + 250 - - - - + + + + + + + + - 165 - 165 - 165 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + 4 + + Qt::Horizontal - QSizePolicy::Preferred + QSizePolicy::Expanding - 1000 - 10 + 474 + 13 - + + + + 0 + 0 + + 51 28 + + Takes you to the online wiki page for Stick settings + QPushButton { border: 1px outset #999; @@ -7428,7 +7495,7 @@ border-radius: 4; - + @@ -7442,6 +7509,9 @@ border-radius: 4; 28 + + Reset all values to GCS defaults + QPushButton { border: 1px outset #999; @@ -7474,3731 +7544,3063 @@ border-radius: 4; - - - - - 0 - 0 - - - - - 0 - 161 - - - - - 16777215 - 161 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - + + + + + + + 0 + 0 + + + + + 0 + 161 + + + + + 16777215 + 180 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + - 58 - 58 - 58 + 36 + 36 + 36 - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 48 - 48 - 48 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 26 - 26 - 26 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 0 - 0 - 0 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 255 - 255 - 220 + 74 + 74 + 74 - - - - + + - 0 - 0 - 0 + 36 + 36 + 36 - - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + - 58 - 58 - 58 + 36 + 36 + 36 - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 48 - 48 - 48 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 26 - 26 - 26 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + - 58 - 58 - 58 + 36 + 36 + 36 - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 48 - 48 - 48 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 26 - 26 - 26 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 0 - 0 - 0 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 255 - 255 - 220 + 74 + 74 + 74 - - - - + + - 0 - 0 - 0 + 36 + 36 + 36 - - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + - 58 - 58 - 58 + 36 + 36 + 36 - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 48 - 48 - 48 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 26 - 26 - 26 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + - 58 - 58 - 58 + 36 + 36 + 36 - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 48 - 48 - 48 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 26 - 26 - 26 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 0 - 0 - 0 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 255 - 255 - 220 + 74 + 74 + 74 - - - - + + - 0 - 0 - 0 + 36 + 36 + 36 - - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + - 58 - 58 - 58 + 36 + 36 + 36 - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 48 - 48 - 48 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 26 - 26 - 26 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Full Stick + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 69 + 29 + + + + + + + Full Stick Angle (deg) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 180 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:RollMax - haslimits:yes - scale:1.0 - buttongroup:3,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 180 - - - 180 - - - - objname:StabilizationSettings - fieldname:RollMax - haslimits:yes - scale:1.0 - buttongroup:3,10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 3 - 22 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 180 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:PitchMax - haslimits:yes - scale:1.0 - buttongroup:3,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 180 - - - 180 - - - - objname:StabilizationSettings - fieldname:PitchMax - haslimits:yes - scale:1.0 - buttongroup:3,10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 3 - 22 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 180 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:YawMax - haslimits:yes - scale:1.0 - buttongroup:3,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 180 - - - 180 - - - - objname:StabilizationSettings - fieldname:YawMax - haslimits:yes - scale:1.0 - buttongroup:3,10 - - - - - - - - - 0 - 0 - - - - - - - Full Stick + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 180 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:RollMax + haslimits:yes + scale:1.0 + buttongroup:3,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 180 + + + 180 + + + + objname:StabilizationSettings + fieldname:RollMax + haslimits:yes + scale:1.0 + buttongroup:3,10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 3 + 22 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 180 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:PitchMax + haslimits:yes + scale:1.0 + buttongroup:3,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 180 + + + 180 + + + + objname:StabilizationSettings + fieldname:PitchMax + haslimits:yes + scale:1.0 + buttongroup:3,10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 3 + 22 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 180 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:YawMax + haslimits:yes + scale:1.0 + buttongroup:3,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 180 + + + 180 + + + + objname:StabilizationSettings + fieldname:YawMax + haslimits:yes + scale:1.0 + buttongroup:3,10 + + + + + + + + + 0 + 0 + + + + + 69 + 29 + + + + + + + Full Stick Rate (deg/s) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 500 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Roll - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 500 - - - 180 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Roll - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 500 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Pitch - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 500 - - - 180 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Pitch - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 500 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Yaw - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 500 - - - 180 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Yaw - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 0 - 0 - - - - - - - Max Rate in + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 500 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Roll + haslimits:yes + scale:1 + buttongroup:3,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 500 + + + 180 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Roll + haslimits:yes + scale:1 + buttongroup:3,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 500 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Pitch + haslimits:yes + scale:1 + buttongroup:3,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 500 + + + 180 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Pitch + haslimits:yes + scale:1 + buttongroup:3,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 500 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Yaw + haslimits:yes + scale:1 + buttongroup:3,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 500 + + + 180 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Yaw + haslimits:yes + scale:1 + buttongroup:3,10 + + + + + + + + + 0 + 0 + + + + + 69 + 29 + + + + + + + Max Rate in Attitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 500 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Roll - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 500 - - - 200 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Roll - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 500 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Pitch - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 500 - - - 200 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Pitch - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 500 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Yaw - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 43 - 22 - - - - - 43 - 22 - - - - Qt::StrongFocus - - - 500 - - - 200 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Yaw - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 180 - - - - - - - - - 0 - 0 - - - - - 0 - 79 - - - - - 16777215 - 79 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - - 0 - 0 - - - - - 239 - 20 - - - - When the throttle is low, zero the intergral term to prevent intergral wind-up - - - - - - Zero the integral when throttle is low - - - - objname:StabilizationSettings - fieldname:LowThrottleZeroIntegral - - - - - - - - - 0 - 0 - - - - - 136 - 20 - - - - If you check this, the GCS will udpate the stabilization factors -automatically every 300ms, which will help for fast tuning. - - - - - - Update in real time - - - - - - - Qt::Horizontal - - - - 111 - 10 - - - - - - - - - 120 - 28 - - - - Reloads the saved settings into GCS. -Useful if you have accidentally changed some settings. - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Reload Board Data - - - - button:reload - buttongroup:10 - - - - - - - - - 60 - 28 - - - - Send settings to the board but do not save to the non-volatile memory - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Apply - - - - button:apply - - - - - - - - - 60 - 28 - - - - Send settings to the board and save to the non-volatile memory - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Save - - - - button:save - - - - - - - - - - - - - - - - Expert - - - - - - QFrame::NoFrame + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 500 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Roll + haslimits:yes + scale:1 + buttongroup:3,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 500 + + + 200 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Roll + haslimits:yes + scale:1 + buttongroup:3,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 500 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Pitch + haslimits:yes + scale:1 + buttongroup:3,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 500 + + + 200 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Pitch + haslimits:yes + scale:1 + buttongroup:3,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 500 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Yaw + haslimits:yes + scale:1 + buttongroup:3,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 500 + + + 200 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Yaw + haslimits:yes + scale:1 + buttongroup:3,10 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Preferred + + + + 20 + 180 + + + + + + + + + + + + + Expert + + + + 12 + + + + + QFrame::NoFrame + + + true + + + + + 0 + 0 + 717 + 923 + + + + true + + + + 12 - - true - - - - - 0 - 0 - 673 - 981 - - - - + + + Qt::Horizontal @@ -11214,7 +10616,7 @@ border-radius: 4; - + @@ -11227,567 +10629,558 @@ border-radius: 4; - - - - - 0 - 0 - - - - - 0 - 210 - - - - - 16777215 - 210 - - - - - - - + + + + + + + 0 + 0 + + + + + 0 + 210 + + + + + 16777215 + 210 + + + + + + + + + 0 + 0 + 0 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + - 255 - 255 - 255 + 250 + 250 + 250 - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + - 251 - 251 - 251 + 243 + 243 + 243 - - - - + + - 124 - 124 - 124 + 250 + 250 + 250 - - - - + + + + + + + + - 165 - 165 - 165 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + - 255 - 255 - 255 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - + + - 251 - 251 - 251 + 250 + 250 + 250 - - - - + + + + + + + + - 255 - 255 - 220 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + - 255 - 255 - 255 + 250 + 250 + 250 - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + - 251 - 251 - 251 + 243 + 243 + 243 - - - - + + - 124 - 124 - 124 + 250 + 250 + 250 - - - - + + + + + + + + - 165 - 165 - 165 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - false - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + + + -1 + + @@ -11797,7 +11190,7 @@ border-radius: 4; - + @@ -11850,2866 +11243,2857 @@ border-radius: 4; - - - - - 0 - 0 - - - - - 0 - 151 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - 2 + + + + + + + 0 + 0 + + + + + 0 + 151 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + 2 + + + + + Qt::Horizontal - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 110 - 13 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - + + QSizePolicy::Fixed + + + + 110 + 13 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + - 58 - 58 - 58 + 36 + 36 + 36 - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 48 - 48 - 48 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 26 - 26 - 26 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 0 - 0 - 0 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 255 - 255 - 220 + 74 + 74 + 74 - - - - + + - 0 - 0 - 0 + 36 + 36 + 36 - - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + - 58 - 58 - 58 + 36 + 36 + 36 - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 48 - 48 - 48 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 26 - 26 - 26 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + - 58 - 58 - 58 + 36 + 36 + 36 - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 48 - 48 - 48 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 26 - 26 - 26 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 0 - 0 - 0 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 255 - 255 - 220 + 74 + 74 + 74 - - - - + + - 0 - 0 - 0 + 36 + 36 + 36 - - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + - 58 - 58 - 58 + 36 + 36 + 36 - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 48 - 48 - 48 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 26 - 26 - 26 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + - 58 - 58 - 58 + 36 + 36 + 36 - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 48 - 48 - 48 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 26 - 26 - 26 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 0 - 0 - 0 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 255 - 255 - 220 + 74 + 74 + 74 - - - - + + - 0 - 0 - 0 + 36 + 36 + 36 - - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + - 255 - 255 - 255 + 74 + 74 + 74 - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - + + - 58 - 58 - 58 + 36 + 36 + 36 - - - - + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + - 48 - 48 - 48 + 74 + 74 + 74 - - - - + + - 19 - 19 - 19 + 36 + 36 + 36 - - - - + + + + + + + + - 26 - 26 - 26 + 74 + 74 + 74 - - - - + + - 255 - 255 - 255 + 36 + 36 + 36 - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. Then lower the value by 20% or so. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. Then lower the value by 20% or so. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. Then lower the value by 20% or so. You can usually go for higher values for Yaw factors. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same value as the Kp. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same value as the Kp. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same value as the Kp. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 58 - 0 - - - - - 16777215 - 16777215 - - - - - - - Derivative - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 50 - 0 - - - - - 16777215 - 16777215 - - - - - - - ILimit - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 58 + 0 + + + + + 16777215 + 16777215 + + + + + + + Derivative + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 50 + 0 + + + + + 16777215 + 16777215 + + + + + + + ILimit + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + + + + + Qt::Horizontal @@ -14725,7 +14109,7 @@ value as the Kp. - + @@ -14738,3218 +14122,571 @@ value as the Kp. - - - - - 0 - 0 - - - - - 0 - 181 - - - - - 16777215 - 181 - - - - - - - + + + + + + + 0 + 0 + + + + + 0 + 181 + + + + + 16777215 + 181 + + + + + + + + + 0 + 0 + 0 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + - 255 - 255 - 255 + 250 + 250 + 250 - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + - 251 - 251 - 251 + 243 + 243 + 243 - - - - + + - 124 - 124 - 124 + 250 + 250 + 250 - - - - + + + + + + + + - 165 - 165 - 165 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + - 255 - 255 - 255 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - + + - 251 - 251 - 251 + 250 + 250 + 250 - - - - + + + + + + + + - 255 - 255 - 220 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + - 255 - 255 - 255 + 250 + 250 + 250 - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + - 251 - 251 - 251 + 243 + 243 + 243 - - - - + + - 124 - 124 - 124 + 250 + 250 + 250 - - - - + + + + + + + + - 165 - 165 - 165 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - false - - - - - - - 0 - 0 - - - - - 0 - 131 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + + + -1 + + + - - + + Link Roll and Pitch - - true - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 110 - 13 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 50 - 0 - - - - - 16777215 - 16777215 - - - - - - - ILimit - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:ILimit - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:ILimit - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:ILimit - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - + @@ -17969,6 +14706,9 @@ border-radius: 5; 28 + + Reset all values to GCS defaults + QPushButton { border: 1px outset #999; @@ -18002,33 +14742,2662 @@ border-radius: 4; - - - - - - - Link Roll and Pitch - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - + + + + + + 0 + 0 + + + + + 0 + 131 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 110 + 13 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Ki + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Ki + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Ki + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 50 + 0 + + + + + 16777215 + 16777215 + + + + + + + ILimit + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:ILimit + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:ILimit + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:YawPI + element:ILimit + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + + + + + Qt::Horizontal @@ -18044,7 +17413,7 @@ border-radius: 4; - + @@ -18057,571 +17426,593 @@ border-radius: 4; - - - - - 0 - 0 - - - - - 0 - 211 - - - - - 16777215 - 211 - - - - - - - + + + + + + + 0 + 0 + + + + + 0 + 211 + + + + + 16777215 + 211 + + + + + + + + + 0 + 0 + 0 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + - 255 - 255 - 255 + 250 + 250 + 250 - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + - 251 - 251 - 251 + 243 + 243 + 243 - - - - + + - 124 - 124 - 124 + 250 + 250 + 250 - - - - + + + + + + + + - 165 - 165 - 165 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + - 255 - 255 - 255 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - + + - 251 - 251 - 251 + 250 + 250 + 250 - - - - + + + + + + + + - 255 - 255 - 220 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + - 255 - 255 - 255 + 250 + 250 + 250 - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + - 251 - 251 - 251 + 243 + 243 + 243 - - - - + + - 124 - 124 - 124 + 250 + 250 + 250 - - - - + + + + + + + + - 165 - 165 - 165 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + -1 + + Qt::Horizontal - QSizePolicy::Preferred + QSizePolicy::Expanding - 10000 + 100 10 - + + + + 0 + 0 + + 81 28 + + + 81 + 28 + + + + Reset all values to GCS defaults + QPushButton { border: 1px outset #999; @@ -18655,3261 +18046,3271 @@ border-radius: 4; - - - - - 0 - 0 - - - - - 0 - 160 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 110 - 13 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Full stick -angle(deg) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:RollMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:PitchMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - - - Full stick rate -rate(deg/s) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Roll - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Pitch - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Yaw - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 50 - 0 - - - - - 16777215 - 16777215 - - - - - - - Max rate in attitude - mode(deg/s) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Roll - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Pitch - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Yaw - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:YawMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - - - - - 180 - 16 - - - - Sensor Tunning - - - - - - - - 0 - 125 - - - - - 16777215 - 125 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - 2 + + + + + + 0 + 0 + - + + + 0 + 160 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 110 + 13 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 69 + 30 + + + + + + + Full stick +angle(deg) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:RollMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:PitchMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 30 + + + + + + + Full stick rate +rate(deg/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Pitch + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 125 + 30 + + + + + 16777215 + 16777215 + + + + + + + Max rate in attitude + mode(deg/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Pitch + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:YawMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + + + + + + + 180 + 16 + + + + Sensor Tunning + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 20 + 10 + + + + + + + + + 0 + 125 + + + + + 16777215 + 125 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + -1 + + Qt::Horizontal - QSizePolicy::Preferred + QSizePolicy::Expanding @@ -21919,7 +21320,7 @@ rate(deg/s) - + @@ -21939,6 +21340,9 @@ rate(deg/s) 28 + + Reset all values to GCS defaults + QPushButton { border: 1px outset #999; @@ -21972,2991 +21376,3031 @@ border-radius: 4; - - - - - 0 - 0 - - - - - 0 - 70 - - - - - 16777215 - 72 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - GyroTau - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - AccelKp - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - AccelKi - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - GyroTau is a gyro filter, the higher the factor the more filtering is applied to the gyros - - - - - - 3 - - - 1000000.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:GyroTau - haslimits:no - scale:1 - buttongroup:8,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - The proportional term for the accelerometer, the higher this term the more weight the accel is given - - - - - - 3 - - - 1000000.000000000000000 - - - 0.010000000000000 - - - - objname:AttitudeSettings - fieldname:AccelKp - haslimits:no - scale:1 - buttongroup:8,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - The intergral term for the accelerometer within the filter - - - - - - 5 - - - 1000000.000000000000000 - - - 0.000100000000000 - - - - objname:AttitudeSettings - fieldname:AccelKi - haslimits:no - scale:1 - buttongroup:8,20 - - - - - - - - - - - - - - 0 - 0 - - - - - 0 - 79 - - - - - 16777215 - 79 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - - 0 - 0 - - - - - 239 - 20 - - - - When the throttle is low, zero the intergral term to prevent intergral wind-up - - - - - - Zero the integral when throttle is low - - - - objname:StabilizationSettings - fieldname:LowThrottleZeroIntegral - - - - - - - - - 0 - 0 - - - - If you check this, the GCS will udpate the stabilization factors + + + + + + 0 + 0 + + + + + 0 + 70 + + + + + 16777215 + 72 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + GyroTau + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + AccelKp + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + AccelKi + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + GyroTau is a gyro filter, the higher the factor the more filtering is applied to the gyros + + + + + + 3 + + + 1000000.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:GyroTau + haslimits:no + scale:1 + buttongroup:8,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + The proportional term for the accelerometer, the higher this term the more weight the accel is given + + + + + + 3 + + + 1000000.000000000000000 + + + 0.010000000000000 + + + + objname:AttitudeSettings + fieldname:AccelKp + haslimits:no + scale:1 + buttongroup:8,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + The intergral term for the accelerometer within the filter + + + + + + 5 + + + 1000000.000000000000000 + + + 0.000100000000000 + + + + objname:AttitudeSettings + fieldname:AccelKi + haslimits:no + scale:1 + buttongroup:8,20 + + + + + + + + + + + + + + + + + + + + + + + 0 + 0 + + + + + 0 + 79 + + + + + 16777215 + 79 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + 12 + + + 12 + + + + + + + + 0 + 0 + + + + + 300 + 20 + + + + When the throttle is low, zero the intergral term to prevent intergral wind-up + + + + + + Zero the integral when throttle is low + + + + objname:StabilizationSettings + fieldname:LowThrottleZeroIntegral + + + + + + + + + 130 + 28 + + + + + 130 + 28 + + + + Reloads the saved settings into GCS. +Useful if you have accidentally changed some settings. + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Reload Board Data + + + + button:reload + buttongroup:10 + + + + + + + + + 60 + 28 + + + + + 60 + 28 + + + + Send settings to the board but do not save to the non-volatile memory + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Apply + + + + button:apply + + + + + + + + + 60 + 28 + + + + + 60 + 28 + + + + Send settings to the board and save to the non-volatile memory + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Save + + + + button:save + + + + + + + + + 0 + 0 + + + + + 136 + 20 + + + + If you check this, the GCS will udpate the stabilization factors automatically every 300ms, which will help for fast tuning. - - - - - - Update in real time - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 60 - 28 - - - - - 60 - 28 - - - - Send settings to the board but do not save to the non-volatile memory - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Apply - - - - button:apply - - - - - - - - - 0 - 0 - - - - - 60 - 28 - - - - - 60 - 28 - - - - Send settings to the board and save to the non-volatile memory - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Save - - - - button:save - - - - - - - - - - - - - - - - + + + + + + Update in real time + + + + + + + - tabWidget scrollArea checkBox_7 pushButton_19 @@ -25053,10 +24497,6 @@ border-radius: 4; GyroTau AccelKp AccelKi - lowThrottleZeroIntegral_9 - realTimeUpdates_7 - saveStabilizationToRAM_7 - saveStabilizationToSD_7 diff --git a/ground/openpilotgcs/src/plugins/config/txpid.ui b/ground/openpilotgcs/src/plugins/config/txpid.ui index 6ffa2e62d..c10a16c6a 100644 --- a/ground/openpilotgcs/src/plugins/config/txpid.ui +++ b/ground/openpilotgcs/src/plugins/config/txpid.ui @@ -6,39 +6,67 @@ 0 0 - 720 - 567 + 708 + 880 - Form + TxPID + + 12 + - - - QFrame::NoFrame + + + 0 - - true - - - - - 0 - 0 - 696 - 475 - - - + + + Tx PID + + + + 12 + + + 12 + + + 12 + - - - Qt::StrongFocus + + + QFrame::NoFrame - - This module will periodically update values of stabilization PID settings + + true + + + + + 0 + 0 + 654 + 671 + + + + + + + + + + + + + Qt::StrongFocus + + + This module will periodically update values of stabilization PID settings depending on configured input control channels. New values of stabilization settings are not saved to flash, but updated in RAM. It is expected that the module will be enabled only for tuning. When desired values are found, they @@ -46,156 +74,152 @@ can be read via GCS and saved permanently. Then this module should be disabled again. Up to 3 separate PID options (or option pairs) can be selected and updated. - - - Enable TxPID module - - - - - - - After enabling the module, you must power cycle before using and configuring. - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 10 - - - - - - - - true - - - - 0 - 0 - - - - - 0 - 100 - - - - Module Settings - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + Enable TxPID module + + + + + + + After enabling the module, you must power cycle before using and configuring. + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Preferred + + + + 20 + 10 + + + + + + + + true + + + + 0 + 0 + + + + + 0 + 100 + + + + Module Settings + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - PID option - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + PID option + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - Control Source - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + Control Source + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - Min - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + Min + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - Max - - - Qt::AlignCenter - - - - - - - Instance 1 - - - - - - - Qt::StrongFocus - - - Select PID option or option pair to update. + + + Max + + + Qt::AlignCenter + + + + + + + Instance 1 + + + + + + + Qt::StrongFocus + + + Select PID option or option pair to update. Set to Disabled if not used. - - - - - - - Qt::StrongFocus - - - Select input used as a control source for this instance. + + + + + + + Qt::StrongFocus + + + Select input used as a control source for this instance. It can be one of Accessory channels or Throttle channel. If Accessory channel is chosen then its range [0..1] will be mapped @@ -209,68 +233,68 @@ accordingly. Note that it is possible to set PID Min > Max. In that case increasing control input value will decrease the PID option value. This can be used, for instance, to decrease PID value when increasing Throttle. - - - - - - - Qt::StrongFocus - - - Minimum PID value mapped to Accessory channel = 0 or + + + + + + + Qt::StrongFocus + + + Minimum PID value mapped to Accessory channel = 0 or Throttle channel lesser or equal to Throttle Min value. - - - 6 - - - 0.000100000000000 - - - - - - - Qt::StrongFocus - - - Maximum PID value mapped to Accessory channel = 1 or + + + 6 + + + 0.000100000000000 + + + + + + + Qt::StrongFocus + + + Maximum PID value mapped to Accessory channel = 1 or Throttle channel greater or equal to Throttle Max value. - - - 6 - - - 0.000100000000000 - - - - - - - Instance 2 - - - - - - - Qt::StrongFocus - - - Select PID option or option pair to update. + + + 6 + + + 0.000100000000000 + + + + + + + Instance 2 + + + + + + + Qt::StrongFocus + + + Select PID option or option pair to update. Set to Disabled if not used. - - - - - - - Qt::StrongFocus - - - Select input used as a control source for this instance. + + + + + + + Qt::StrongFocus + + + Select input used as a control source for this instance. It can be one of Accessory channels or Throttle channel. If Accessory channel is chosen then its range [0..1] will be mapped @@ -284,68 +308,68 @@ accordingly. Note that it is possible to set PID Min > Max. In that case increasing control input value will decrease the PID option value. This can be used, for instance, to decrease PID value when increasing Throttle. - - - - - - - Qt::StrongFocus - - - Minimum PID value mapped to Accessory channel = 0 or + + + + + + + Qt::StrongFocus + + + Minimum PID value mapped to Accessory channel = 0 or Throttle channel lesser or equal to Throttle Min value. - - - 6 - - - 0.000100000000000 - - - - - - - Qt::StrongFocus - - - Maximum PID value mapped to Accessory channel = 1 or + + + 6 + + + 0.000100000000000 + + + + + + + Qt::StrongFocus + + + Maximum PID value mapped to Accessory channel = 1 or Throttle channel greater or equal to Throttle Max value. - - - 6 - - - 0.000100000000000 - - - - - - - Instance 3 - - - - - - - Qt::StrongFocus - - - Select PID option or option pair to update. + + + 6 + + + 0.000100000000000 + + + + + + + Instance 3 + + + + + + + Qt::StrongFocus + + + Select PID option or option pair to update. Set to Disabled if not used. - - - - - - - Qt::StrongFocus - - - Select input used as a control source for this instance. + + + + + + + Qt::StrongFocus + + + Select input used as a control source for this instance. It can be one of Accessory channels or Throttle channel. If Accessory channel is chosen then its range [0..1] will be mapped @@ -359,57 +383,57 @@ accordingly. Note that it is possible to set PID Min > Max. In that case increasing control input value will decrease the PID option value. This can be used, for instance, to decrease PID value when increasing Throttle. - - - - - - - Qt::StrongFocus - - - Minimum PID value mapped to Accessory channel = 0 or + + + + + + + Qt::StrongFocus + + + Minimum PID value mapped to Accessory channel = 0 or Throttle channel lesser or equal to Throttle Min value. - - - 6 - - - 0.000100000000000 - - - - - - - Qt::StrongFocus - - - Maximum PID value mapped to Accessory channel = 1 or + + + 6 + + + 0.000100000000000 + + + + + + + Qt::StrongFocus + + + Maximum PID value mapped to Accessory channel = 1 or Throttle channel greater or equal to Throttle Max value. - - - 6 - - - 0.000100000000000 - - - - - - - Update Mode - - - - - - - Qt::StrongFocus - - - PID values update mode which can be set to: + + + 6 + + + 0.000100000000000 + + + + + + + Update Mode + + + + + + + Qt::StrongFocus + + + PID values update mode which can be set to: - Never: this disables PID updates (but module still will be run if enabled), - When Armed: PID updated only when system is armed, - Always: PID updated always regardless of arm state. @@ -419,183 +443,266 @@ tricky to change other PID values from the GUI if the module is enabled and constantly updates stabilization settings object. As a workaround, this option can be used to temporarily disable updates or enable them only when system is armed without disabling the module. - - - - - - - Throttle Range - - - - - - - Qt::StrongFocus - - - Throttle channel lower bound mapped to PID Min value - - - 1.000000000000000 - - - 0.010000000000000 - - - - - - - Qt::StrongFocus - - - Throttle channel upper bound mapped to PID Max value - - - 1.000000000000000 - - - 0.010000000000000 - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + + + + + Throttle Range + + + + + + + Qt::StrongFocus + + + Throttle channel lower bound mapped to PID Min value + + + 1.000000000000000 + + + 0.010000000000000 + + + + + + + Qt::StrongFocus + + + Throttle channel upper bound mapped to PID Max value + + + 1.000000000000000 + + + 0.010000000000000 + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - Min - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + Min + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - Max - - - Qt::AlignCenter - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 20 - - - - - + + + Max + + + Qt::AlignCenter + + + + + + + Qt::Vertical + + + QSizePolicy::Preferred + + + + 20 + 20 + + + + + + + + + + + Qt::Vertical + + + + 20 + 20 + + + + + + - - - - Qt::Vertical - - - - 20 - 20 - - - - - - - - - - - - - - - - - - QFrame::StyledPanel - - - QFrame::Raised - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Send settings to the board but do not save to the non-volatile memory - - - Apply - - - - - - - Send settings to the board and save to the non-volatile memory - - - Save - - - false - - - - - - + + + Messsages + + + + + + + + + + + + + + + + + 0 + 0 + + + + + 16777215 + 79 + + + + + + + + + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 60 + 28 + + + + Send settings to the board but do not save to the non-volatile memory + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Apply + + + + + + + + 60 + 28 + + + + Send settings to the board and save to the non-volatile memory + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Save + + + false + + + + + + + - TxPIDEnable Apply Save scrollArea From e1b469b130ba9c1a272280969102ab51658633c2 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Wed, 11 Jul 2012 21:49:05 -0700 Subject: [PATCH 035/543] MixerCurve: simplified. --- .../src/plugins/config/mixercurve.cpp | 82 ++- .../src/plugins/config/mixercurve.h | 1 + .../src/plugins/config/mixercurve.ui | 633 +++++++++--------- .../uavobjectwidgetutils/mixercurvepoint.cpp | 57 +- .../uavobjectwidgetutils/mixercurvepoint.h | 34 +- .../uavobjectwidgetutils/mixercurvewidget.cpp | 247 ++++++- .../uavobjectwidgetutils/mixercurvewidget.h | 18 + 7 files changed, 705 insertions(+), 367 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index e8da7dbaa..47e16db1f 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -47,18 +47,26 @@ MixerCurve::MixerCurve(QWidget *parent) : // set the default mixer type setMixerType(MixerCurve::MIXERCURVE_THROTTLE); + // setup and turn off advanced mode + CommandActivated(); + // paint the ui UpdateCurveUI(); // wire up our signals + connect(m_mixerUI->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(CurveTypeChanged())); connect(m_mixerUI->ResetCurve, SIGNAL(clicked()), this, SLOT(ResetCurve())); connect(m_mixerUI->GenerateCurve, SIGNAL(clicked()), this, SLOT(GenerateCurve())); connect(m_curve, SIGNAL(curveUpdated()), this, SLOT(UpdateSettingsTable())); + connect(m_curve, SIGNAL(commandActivated(Node*)),this, SLOT(CommandActivated(Node*))); connect(m_settings, SIGNAL(cellChanged(int,int)), this, SLOT(SettingsTableChanged())); connect(m_mixerUI->CurveMin, SIGNAL(valueChanged(double)), this, SLOT(CurveMinChanged(double))); connect(m_mixerUI->CurveMax, SIGNAL(valueChanged(double)), this, SLOT(CurveMaxChanged(double))); connect(m_mixerUI->CurveStep, SIGNAL(valueChanged(double)), this, SLOT(GenerateCurve())); + + + } MixerCurve::~MixerCurve() @@ -86,7 +94,8 @@ void MixerCurve::setMixerType(MixerCurveType curveType) case MixerCurve::MIXERCURVE_PITCH: { m_mixerUI->SettingsGroup->setTitle("Pitch Curve"); - m_curve->setRange(-1.0, 1.0); + m_curve->setRange(-1.0, 1.0); + m_curve->setPositiveColor("#0000ff", "#0000ff"); m_mixerUI->CurveMin->setMinimum(-1.0); m_mixerUI->CurveMax->setMinimum(-1.0); break; @@ -109,6 +118,8 @@ void MixerCurve::ResetCurve() initLinearCurve(MixerCurveWidget::NODE_NUMELEM, getCurveMax(), getCurveMin()); + m_curve->activateCommand("Linear"); + UpdateSettingsTable(); } @@ -117,14 +128,11 @@ void MixerCurve::UpdateCurveUI() //get the user settings QString curveType = m_mixerUI->CurveType->currentText(); - m_mixerUI->CurveMin->setValue(m_mixerUI->CurveMin->minimum()); - m_mixerUI->CurveMax->setValue(m_mixerUI->CurveMax->maximum()); - m_mixerUI->CurveStep->setMinimum(0.0); m_mixerUI->CurveStep->setMaximum(100.0); + m_mixerUI->CurveStep->setSingleStep(1.00); //set default visible - m_mixerUI->minLabel->setText("Min"); m_mixerUI->minLabel->setVisible(true); m_mixerUI->CurveMin->setVisible(true); m_mixerUI->maxLabel->setVisible(false); @@ -134,7 +142,10 @@ void MixerCurve::UpdateCurveUI() if ( curveType.compare("Flat")==0) { - m_mixerUI->minLabel->setText("Value"); + m_mixerUI->CurveStep->setMinimum(m_mixerUI->CurveMin->minimum()); + m_mixerUI->CurveStep->setMaximum(m_mixerUI->CurveMax->maximum()); + m_mixerUI->CurveStep->setSingleStep(0.01); + m_mixerUI->CurveStep->setValue(m_mixerUI->CurveMax->value() / 2); } if ( curveType.compare("Linear")==0) { @@ -155,7 +166,7 @@ void MixerCurve::UpdateCurveUI() { m_mixerUI->maxLabel->setVisible(true); m_mixerUI->CurveMax->setVisible(true); - m_mixerUI->stepLabel->setText("Strength"); + m_mixerUI->stepLabel->setText("Power"); m_mixerUI->stepLabel->setVisible(true); m_mixerUI->CurveStep->setVisible(true); @@ -165,7 +176,7 @@ void MixerCurve::UpdateCurveUI() { m_mixerUI->maxLabel->setVisible(true); m_mixerUI->CurveMax->setVisible(true); - m_mixerUI->stepLabel->setText("Strength"); + m_mixerUI->stepLabel->setText("Power"); m_mixerUI->stepLabel->setVisible(true); m_mixerUI->CurveStep->setVisible(true); m_mixerUI->CurveStep->setMinimum(1.0); @@ -184,6 +195,8 @@ void MixerCurve::GenerateCurve() double value2 = getCurveMax(); double value3 = getCurveStep(); + m_curve->setCommandText("StepValue", QString("%0").arg(value3)); + QString CurveType = m_mixerUI->CurveType->currentText(); QList points; @@ -194,7 +207,7 @@ void MixerCurve::GenerateCurve() if ( CurveType.compare("Flat")==0) { - points.append(value1); + points.append(value3); } if ( CurveType.compare("Linear")==0) { @@ -323,6 +336,57 @@ void MixerCurve::SettingsTableChanged() m_curve->setCurve(&points); } +void MixerCurve::CommandActivated(Node* node) +{ + //m_mixerUI->GenerateCurve->hide(); + + m_mixerUI->SettingsGroup->hide(); + m_mixerUI->ValuesGroup->hide(); + + QString name = (node) ? node->getName() : "Reset"; + + if (name == "Reset") { + ResetCurve(); + } + else if (name == "Linear") { + m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Linear")); + } + else if (name == "Log") { + m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Log")); + } + else if (name == "Exp") { + m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Exp")); + } + else if (name == "Flat") { + m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Flat")); + } + else if (name == "Step") { + m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Step")); + } + else if (name == "MinPlus") { + m_mixerUI->CurveMin->stepUp(); + } + else if (name == "MinMinus") { + m_mixerUI->CurveMin->stepDown(); + } + else if (name == "MaxPlus") { + m_mixerUI->CurveMax->stepUp(); + } + else if (name == "MaxMinus"){ + m_mixerUI->CurveMax->stepDown(); + } + else if (name == "StepPlus") { + m_mixerUI->CurveStep->stepUp(); + m_curve->setCommandText("StepValue", QString("%0").arg(getCurveStep())); + } + else if (name == "StepMinus") { + m_mixerUI->CurveStep->stepDown(); + m_curve->setCommandText("StepValue", QString("%0").arg(getCurveStep())); + } + + GenerateCurve(); +} + void MixerCurve::CurveTypeChanged() { // setup the ui for this curvetype diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.h b/ground/openpilotgcs/src/plugins/config/mixercurve.h index f746dfec7..bd24c46a9 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.h +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.h @@ -82,6 +82,7 @@ public slots: void UpdateSettingsTable(); private slots: + void CommandActivated(Node* node = 0); void SettingsTableChanged(); void CurveTypeChanged(); void CurveMinChanged(double value); diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.ui b/ground/openpilotgcs/src/plugins/config/mixercurve.ui index ad6e8b696..7adf707da 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.ui +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.ui @@ -7,7 +7,7 @@ 0 0 441 - 321 + 334 @@ -43,340 +43,309 @@ QFrame::Raised - - - - - - - QLayout::SetDefaultConstraint - - - - - - 150 - 16777215 - + + + + + + 150 + 16777215 + + + + Throttle Curve + + + + + + + 100 + 200 + + + + + 8 + + + + Qt::ScrollBarAlwaysOff + + + Qt::ScrollBarAlwaysOff + + + false + + + true + + + 5 + + + 1 + + + + Max - - Throttle Curve + + + + 4 - - - - - - 100 - 200 - - - - - 8 - - - - Qt::ScrollBarAlwaysOff - - - Qt::ScrollBarAlwaysOff - - - false - - - true - - - 5 - - - 1 - - - - 5 - - - - - 4 - - - - - 3 - - - - - 2 - - - - - 1 - - - - - Value - - - AlignJustify|AlignVCenter - - - - - 1.0 - - - - - .75 - - - - - .50 - - - - - .25 - - - - - .00 - - - - - - - - - Linear - - - - - Log - - - - - Exp - - - - - Flat - - - - - Step - - - - - - - - Generate - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - Reset - - - - - GenerateCurve - CurveSettings - ResetCurve - CurveType - verticalSpacer - - - - - - - - QLayout::SetDefaultConstraint - - - - - - 1 - 1 - + + + + 3 - - - QLayout::SetMinAndMaxSize - - - - - - 5 - 5 - - - - - 50 - 50 - - - - - 1000 - 1000 - - - - - 10 - 10 - - - - - 200 - 200 - - - - - 7 - - - - - - - - - - - - - - - - Min - - - - - - - QAbstractSpinBox::CorrectToNearestValue - - - -1.000000000000000 - - - 1.000000000000000 - - - 0.010000000000000 - - - 0.000000000000000 - - - - - - - Max - - - - - - - QAbstractSpinBox::CorrectToNearestValue - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.010000000000000 - - - 1.000000000000000 - - - - - - - Step - - - - - - - QAbstractSpinBox::CorrectToNearestValue - - - 50.000000000000000 - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - - - - + + + + 2 + + + + + Min + + + + + Value + + + AlignJustify|AlignVCenter + + + + + 1.0 + + + + + .75 + + + + + .50 + + + + + .25 + + + + + .00 + + + + + + + + + Linear + + + + + Log + + + + + Exp + + + + + Flat + + + + + Step + + + + + + + + Generate + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + Reset + + + + + GenerateCurve + CurveSettings + ResetCurve + CurveType + verticalSpacer + + + + + + + 5 + 5 + + + + + 50 + 50 + + + + + 1000 + 1000 + + + + + 10 + 10 + + + + + 200 + 200 + + + + + 7 + + + + + + + + + + + + + + Min + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + QAbstractSpinBox::CorrectToNearestValue + + + -1.000000000000000 + + + 1.000000000000000 + + + 0.010000000000000 + + + 0.000000000000000 + + + + + + + Max + + + + + + + QAbstractSpinBox::CorrectToNearestValue + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.010000000000000 + + + 1.000000000000000 + + + + + + + Step + + + + + + + QAbstractSpinBox::CorrectToNearestValue + + + 50.000000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp index 5fdd2fbbf..3a6f91b21 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #include "mixercurveline.h" @@ -42,7 +43,16 @@ Node::Node(MixerCurveWidget *graphWidget) setFlag(ItemSendsGeometryChanges); setCacheMode(DeviceCoordinateCache); setZValue(-1); + cmdActive = false; vertical = false; + cmdNode = false; + cmdToggle = true; + + posColor0 = "#1c870b"; //greenish? + posColor1 = "#116703"; //greenish? + negColor0 = "#ff0000"; //red + negColor1 = "#ff0000"; //red + } void Node::addEdge(Edge *edge) @@ -59,53 +69,53 @@ QList Node::edges() const QRectF Node::boundingRect() const { - return QRectF(-13, -13, 26, 26); + return cmdNode ? QRectF(-4, -4, 15, 10) : QRectF(-13, -13, 26, 26); } QPainterPath Node::shape() const { QPainterPath path; - path.addEllipse(-13, -13, 26, 26); + path.addEllipse(boundingRect()); return path; } void Node::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *) { - /* - painter->setPen(Qt::NoPen); - painter->setBrush(Qt::darkGray); - painter->drawEllipse(-7, -7, 20, 20); - */ + QString text = cmdNode ? cmdText : QString().sprintf("% .2f", value()); QRadialGradient gradient(-3, -3, 10); if (option->state & QStyle::State_Sunken) { gradient.setCenter(3, 3); gradient.setFocalPoint(3, 3); - //gradient.setColorAt(1, QColor("#1c870b").light(120)); - //gradient.setColorAt(0, QColor("#116703").light(120)); gradient.setColorAt(1, Qt::darkBlue); gradient.setColorAt(0, Qt::darkBlue); } else { - if (value() < 0) { - gradient.setColorAt(0, Qt::red); - gradient.setColorAt(1, Qt::red); + if (cmdNode) { + gradient.setColorAt(0, cmdActive ? posColor0 : negColor0); + gradient.setColorAt(1, cmdActive ? posColor1 : negColor1); } else { - gradient.setColorAt(0, "#1c870b"); - gradient.setColorAt(1, "#116703"); + if (value() < 0) { + gradient.setColorAt(0, negColor0); + gradient.setColorAt(1, negColor1); + } + else { + gradient.setColorAt(0, posColor0); + gradient.setColorAt(1, posColor1); + } } } painter->setBrush(gradient); painter->setPen(QPen(Qt::black, 0)); - painter->drawEllipse(-13, -13, 26, 26); + painter->drawEllipse(boundingRect()); painter->setPen(QPen(Qt::white, 0)); - if (value() < 0) { - painter->drawText(-13, 4, QString().sprintf("% .2f", value())); + if (cmdNode) { + painter->drawText(0,4,text); } else { - painter->drawText(-11, 4, QString().sprintf("%.2f", value())); + painter->drawText(-13, 4, text); } } @@ -113,6 +123,13 @@ void Node::verticalMove(bool flag){ vertical = flag; } +void Node::commandNode(bool enable){ + cmdNode = enable; +} +void Node::commandText(QString text){ + cmdText = text; +} + double Node::value() { double h = graph->sceneRect().height(); double ratio = (h - pos().y()) / h; @@ -161,6 +178,10 @@ QVariant Node::itemChange(GraphicsItemChange change, const QVariant &val) void Node::mousePressEvent(QGraphicsSceneMouseEvent *event) { + if (cmdNode) { + graph->cmdActivated(this); + //return; + } update(); QGraphicsItem::mousePressEvent(event); } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h index eca445d32..1747f1679 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h @@ -29,6 +29,7 @@ #define MIXERCURVEPOINT_H #include +#include #include class Edge; @@ -48,8 +49,20 @@ public: enum { Type = UserType + 1 }; int type() const { return Type; } + void setName(QString name) { cmdName = name; } + const QString& getName() { return cmdName; } void verticalMove(bool flag); + void commandNode(bool enable); + void commandText(QString text); + int getCommandIndex() { return index; } + void setCommandIndex(int idx) { index = idx; } + void setActive(bool enable) { cmdActive = enable; } + void setToggle(bool enable) { cmdToggle = enable; } + bool getToggle() { return cmdToggle; } + + void setPositiveColor(QString color0 = "#00ff00", QString color1 = "#00ff00") { posColor0 = color0; posColor1 = color1; } + void setNegativeColor(QString color0 = "#ff0000", QString color1 = "#ff0000") { negColor0 = color0; negColor1 = color1; } QRectF boundingRect() const; QPainterPath shape() const; @@ -57,6 +70,9 @@ public: double value(); +signals: + void commandActivated(QString text); + protected: QVariant itemChange(GraphicsItemChange change, const QVariant &val); @@ -64,11 +80,21 @@ protected: void mouseReleaseEvent(QGraphicsSceneMouseEvent *event); private: + QList edgeList; + QPointF newPos; + MixerCurveWidget* graph; + QString posColor0; + QString posColor1; + QString negColor0; + QString negColor1; - QList edgeList; - QPointF newPos; - MixerCurveWidget *graph; - bool vertical; + bool vertical; + QString cmdName; + bool cmdActive; + bool cmdNode; + bool cmdToggle; + QString cmdText; + int index; }; diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index 3833b18ed..bff81f98a 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -29,6 +29,7 @@ #include "mixercurveline.h" #include "mixercurvepoint.h" +#include #include #include @@ -57,7 +58,6 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) curveMin=0.0; curveMax=1.0; - setFrameStyle(QFrame::NoFrame); setStyleSheet("background:transparent"); @@ -73,7 +73,111 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) scene->setSceneRect(plot->boundingRect()); setScene(scene); + posColor0 = "#1c870b"; //greenish? + posColor1 = "#116703"; //greenish? + negColor0 = "#ff0000"; //red + negColor1 = "#ff0000"; //red + + // commmand nodes + // reset + Node* node = getCommandNode(0); + node->setName("Reset"); + node->setToggle(false); + node->setPositiveColor("#ffffff", "#ffffff"); //white + node->setNegativeColor("#ffffff", "#ffffff"); + scene->addItem(node); + + // linear + node = getCommandNode(1); + node->setName("Linear"); + node->commandText("/"); + scene->addItem(node); + + // log + node = getCommandNode(2); + node->setName("Log"); + node->commandText("("); + scene->addItem(node); + + // exp + node = getCommandNode(3); + node->setName("Exp"); + node->commandText(")"); + scene->addItem(node); + + // flat + node = getCommandNode(4); + node->setName("Flat"); + node->commandText("--"); + scene->addItem(node); + + // step + node = getCommandNode(5); + node->setName("Step"); + node->commandText("z"); + scene->addItem(node); + + + // curve min/max nodes + node = getCommandNode(6); + node->setName("MinPlus"); + node->setToggle(false); + node->setPositiveColor("#00ff00", "#00ff00"); //green + node->setNegativeColor("#00ff00", "#00ff00"); + node->commandText("+"); + scene->addItem(node); + + node = getCommandNode(7); + node->setName("MinMinus"); + node->setToggle(false); + node->setPositiveColor("#ff0000", "#ff0000"); //red + node->setNegativeColor("#ff0000", "#ff0000"); + node->commandText("-"); + scene->addItem(node); + + node = getCommandNode(8); + node->setName("MaxPlus"); + node->setToggle(false); + node->setPositiveColor("#00ff00", "#00ff00"); //green + node->setNegativeColor("#00ff00", "#00ff00"); + node->commandText("+"); + scene->addItem(node); + + node = getCommandNode(9); + node->setName("MaxMinus"); + node->setToggle(false); + node->setPositiveColor("#ff0000", "#ff0000"); //red + node->setNegativeColor("#ff0000", "#ff0000"); + node->commandText("-"); + scene->addItem(node); + + node = getCommandNode(10); + node->setName("StepPlus"); + node->setToggle(false); + node->setPositiveColor("#00ff00", "#00ff00"); //green + node->setNegativeColor("#00ff00", "#00ff00"); + node->commandText("+"); + scene->addItem(node); + + node = getCommandNode(11); + node->setName("StepMinus"); + node->setToggle(false); + node->setPositiveColor("#ff0000", "#ff0000"); //red + node->setNegativeColor("#ff0000", "#ff0000"); + node->commandText("-"); + scene->addItem(node); + + node = getCommandNode(12); + node->setName("StepValue"); + node->setToggle(false); + node->setPositiveColor("#0000ff", "#0000ff"); //blue + node->setNegativeColor("#0000ff", "#0000ff"); + scene->addItem(node); + + resizeCommands(); + initNodes(MixerCurveWidget::NODE_NUMELEM); + } MixerCurveWidget::~MixerCurveWidget() @@ -83,6 +187,30 @@ MixerCurveWidget::~MixerCurveWidget() while (!edgePool.isEmpty()) delete edgePool.takeFirst(); + + while (!cmdNodePool.isEmpty()) + delete cmdNodePool.takeFirst(); +} + +Node* MixerCurveWidget::getCommandNode(int index) +{ + Node* node; + + if (index >= 0 && index < cmdNodePool.count()) + { + node = cmdNodePool.at(index); + } + else { + node = new Node(this); + node->commandNode(true); + node->commandText(""); + node->setCommandIndex(index); + node->setActive(false); + node->setPositiveColor("#ff0000", "#ff0000"); + node->setNegativeColor("#0000cc", "#0000cc"); + cmdNodePool.append(node); + } + return node; } Node* MixerCurveWidget::getNode(int index) @@ -99,7 +227,6 @@ Node* MixerCurveWidget::getNode(int index) } return node; } - Edge* MixerCurveWidget::getEdge(int index, Node* sourceNode, Node* destNode) { Edge* edge; @@ -117,6 +244,26 @@ Edge* MixerCurveWidget::getEdge(int index, Node* sourceNode, Node* destNode) return edge; } +void MixerCurveWidget::setPositiveColor(QString color0, QString color1) +{ + posColor0 = color0; + posColor1 = color1; + for (int i=0; isetPositiveColor(color0, color1); + } +} +void MixerCurveWidget::setNegativeColor(QString color0, QString color1) +{ + negColor0 = color0; + negColor1 = color1; + for (int i=0; isetNegativeColor(color0, color1); + } +} + + /** Init curve: create a (flat) curve with a specified number of points. @@ -220,6 +367,10 @@ void MixerCurveWidget::setCurve(const QList* points) Node* node = nodeList.at(i); node->setPos(w*i, h - (val*h)); node->verticalMove(true); + + node->setPositiveColor(posColor0, posColor1); + node->setNegativeColor(negColor0, negColor1); + node->update(); } curveUpdating = false; @@ -238,7 +389,7 @@ void MixerCurveWidget::showEvent(QShowEvent *event) // the result is usually a ahrsbargraph that is way too small. QRectF rect = plot->boundingRect(); - + resizeCommands(); fitInView(rect.adjusted(-15,-15,15,15), Qt::KeepAspectRatio); } @@ -247,12 +398,54 @@ void MixerCurveWidget::resizeEvent(QResizeEvent* event) Q_UNUSED(event); QRectF rect = plot->boundingRect(); - + resizeCommands(); fitInView(rect.adjusted(-15,-15,15,15), Qt::KeepAspectRatio); } +void MixerCurveWidget::resizeCommands() +{ + QRectF rect = plot->boundingRect(); + + Node* node; + for (int i = 0; i<6; i++) { + node = getCommandNode(i); + + node->setPos((rect.left() + rect.width() / 2) - 60 + (i * 20), rect.height() + 10); + } + + //curveminplus + node = getCommandNode(6); + node->setPos(rect.bottomLeft().x() + 15, rect.bottomLeft().y() - 10); + + //curveminminus + node = getCommandNode(7); + node->setPos(rect.bottomLeft().x() + 15, rect.bottomLeft().y() + 5); + + //curvemaxplus + node = getCommandNode(8); + node->setPos(rect.topRight().x() - 20, rect.topRight().y() - 7); + + //curvemaxminus + node = getCommandNode(9); + node->setPos(rect.topRight().x() - 20, rect.topRight().y() + 8); + + //stepplus + node = getCommandNode(10); + node->setPos(rect.bottomRight().x() - 60, rect.bottomRight().y() + 8); + + //stepminus + node = getCommandNode(11); + node->setPos(rect.bottomRight().x() - 40, rect.bottomRight().y() + 8); + + //step + node = getCommandNode(12); + node->setPos(rect.bottomRight().x() - 20, rect.bottomRight().y() + 8); +} + void MixerCurveWidget::itemMoved(double itemValue) { + Q_UNUSED(itemValue); + if (!curveUpdating) { emit curveUpdated(); } @@ -288,3 +481,49 @@ double MixerCurveWidget::setRange(double min, double max) curveMax = max; return curveMax - curveMin; } + +Node* MixerCurveWidget::getCmdNode(const QString& name) +{ + Node* node = 0; + for (int i=0; igetName() == name) + node = n; + } + return node; +} + +void MixerCurveWidget::setCommandText(const QString& name, const QString& text) +{ + for (int i=0; igetName() == name) { + n->commandText(text); + n->update(); + } + } +} +void MixerCurveWidget::activateCommand(const QString& name) +{ + for (int i=0; isetActive(node->getName() == name); + node->update(); + } +} + +void MixerCurveWidget::cmdActivated(Node* node) +{ + if (node->getToggle()) { + for (int i=0; isetActive(false); + n->update(); + } + + node->setActive(true); + } + node->update(); + emit commandActivated(node); +} + diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h index dcf9dc93a..3747730a0 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h @@ -28,6 +28,7 @@ #ifndef MIXERCURVEWIDGET_H_ #define MIXERCURVEWIDGET_H_ +#include #include #include #include @@ -57,12 +58,18 @@ public: double getMax(); double setRange(double min, double max); + void cmdActivated(Node* node); + void activateCommand(const QString& name); + Node* getCmdNode(const QString& name); + void setCommandText(const QString& name, const QString& text); + static const int NODE_NUMELEM = 5; signals: void curveUpdated(); void curveMinChanged(double value); void curveMaxChanged(double value); + void commandActivated(Node* node); private slots: @@ -70,6 +77,7 @@ private: QGraphicsSvgItem *plot; QList nodePool; + QList cmdNodePool; QList edgePool; QList nodeList; @@ -77,9 +85,19 @@ private: double curveMax; bool curveUpdating; + QString posColor0; + QString posColor1; + QString negColor0; + QString negColor1; + void initNodes(int numPoints); Node* getNode(int index); + Node* getCommandNode(int index); Edge* getEdge(int index, Node* sourceNode, Node* destNode); + void setPositiveColor(QString color0 = "#00ff00", QString color1 = "#00ff00"); + void setNegativeColor(QString color0 = "#ff0000", QString color1 = "#ff0000"); + + void resizeCommands(); protected: void showEvent(QShowEvent *event); From a5e117101bc046b2e831749a3687f1845245767b Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Thu, 12 Jul 2012 10:49:22 -0700 Subject: [PATCH 036/543] Mixercurve, change command location/colors; add tooltips; subdue node colors. --- .../src/plugins/config/mixercurve.cpp | 2 +- .../uavobjectwidgetutils/mixercurvepoint.cpp | 4 +- .../uavobjectwidgetutils/mixercurvewidget.cpp | 68 ++++++++++++------- 3 files changed, 48 insertions(+), 26 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 47e16db1f..73593dca9 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -95,7 +95,7 @@ void MixerCurve::setMixerType(MixerCurveType curveType) { m_mixerUI->SettingsGroup->setTitle("Pitch Curve"); m_curve->setRange(-1.0, 1.0); - m_curve->setPositiveColor("#0000ff", "#0000ff"); + m_curve->setPositiveColor("#0000aa", "#0000aa"); m_mixerUI->CurveMin->setMinimum(-1.0); m_mixerUI->CurveMax->setMinimum(-1.0); break; diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp index 3a6f91b21..856f44b56 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp @@ -50,8 +50,8 @@ Node::Node(MixerCurveWidget *graphWidget) posColor0 = "#1c870b"; //greenish? posColor1 = "#116703"; //greenish? - negColor0 = "#ff0000"; //red - negColor1 = "#ff0000"; //red + negColor0 = "#aa0000"; //red + negColor1 = "#aa0000"; //red } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index bff81f98a..04464d9d8 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -82,6 +82,7 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) // reset Node* node = getCommandNode(0); node->setName("Reset"); + node->setToolTip("Reset Curve to Defaults"); node->setToggle(false); node->setPositiveColor("#ffffff", "#ffffff"); //white node->setNegativeColor("#ffffff", "#ffffff"); @@ -90,30 +91,35 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) // linear node = getCommandNode(1); node->setName("Linear"); + node->setToolTip("Generate a Linear Curve"); node->commandText("/"); scene->addItem(node); // log node = getCommandNode(2); node->setName("Log"); + node->setToolTip("Generate a Logarithmic Curve"); node->commandText("("); scene->addItem(node); // exp node = getCommandNode(3); node->setName("Exp"); + node->setToolTip("Generate an Exponential Curve"); node->commandText(")"); scene->addItem(node); // flat node = getCommandNode(4); node->setName("Flat"); + node->setToolTip("Generate a Flat Curve"); node->commandText("--"); scene->addItem(node); // step node = getCommandNode(5); node->setName("Step"); + node->setToolTip("Generate a Stepped Curve"); node->commandText("z"); scene->addItem(node); @@ -121,57 +127,64 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) // curve min/max nodes node = getCommandNode(6); node->setName("MinPlus"); + node->setToolTip("Increase Curve Minimum"); node->setToggle(false); - node->setPositiveColor("#00ff00", "#00ff00"); //green - node->setNegativeColor("#00ff00", "#00ff00"); + node->setPositiveColor("#00aa00", "#00aa00"); //green + node->setNegativeColor("#00aa00", "#00aa00"); node->commandText("+"); scene->addItem(node); node = getCommandNode(7); node->setName("MinMinus"); + node->setToolTip("Decrease Curve Minimum"); node->setToggle(false); - node->setPositiveColor("#ff0000", "#ff0000"); //red - node->setNegativeColor("#ff0000", "#ff0000"); + node->setPositiveColor("#aa0000", "#aa0000"); //red + node->setNegativeColor("#aa0000", "#aa0000"); node->commandText("-"); scene->addItem(node); node = getCommandNode(8); node->setName("MaxPlus"); + node->setToolTip("Increase Curve Maximum"); node->setToggle(false); - node->setPositiveColor("#00ff00", "#00ff00"); //green - node->setNegativeColor("#00ff00", "#00ff00"); + node->setPositiveColor("#00aa00", "#00aa00"); //green + node->setNegativeColor("#00aa00", "#00aa00"); node->commandText("+"); scene->addItem(node); node = getCommandNode(9); node->setName("MaxMinus"); + node->setToolTip("Decrease Curve Maximum"); node->setToggle(false); - node->setPositiveColor("#ff0000", "#ff0000"); //red - node->setNegativeColor("#ff0000", "#ff0000"); + node->setPositiveColor("#aa0000", "#aa0000"); //red + node->setNegativeColor("#aa0000", "#aa0000"); node->commandText("-"); scene->addItem(node); node = getCommandNode(10); node->setName("StepPlus"); + node->setToolTip("Increase Step/Power Value"); node->setToggle(false); - node->setPositiveColor("#00ff00", "#00ff00"); //green - node->setNegativeColor("#00ff00", "#00ff00"); + node->setPositiveColor("#00aa00", "#00aa00"); //green + node->setNegativeColor("#00aa00", "#00aa00"); node->commandText("+"); scene->addItem(node); node = getCommandNode(11); node->setName("StepMinus"); + node->setToolTip("Decrease Step/Power Value"); node->setToggle(false); - node->setPositiveColor("#ff0000", "#ff0000"); //red - node->setNegativeColor("#ff0000", "#ff0000"); + node->setPositiveColor("#aa0000", "#aa0000"); //red + node->setNegativeColor("#aa0000", "#aa0000"); node->commandText("-"); scene->addItem(node); node = getCommandNode(12); node->setName("StepValue"); + node->setToolTip("Current Step/Power Value"); node->setToggle(false); - node->setPositiveColor("#0000ff", "#0000ff"); //blue - node->setNegativeColor("#0000ff", "#0000ff"); + node->setPositiveColor("#0000aa", "#0000aa"); //blue + node->setNegativeColor("#0000aa", "#0000aa"); scene->addItem(node); resizeCommands(); @@ -206,8 +219,8 @@ Node* MixerCurveWidget::getCommandNode(int index) node->commandText(""); node->setCommandIndex(index); node->setActive(false); - node->setPositiveColor("#ff0000", "#ff0000"); - node->setNegativeColor("#0000cc", "#0000cc"); + node->setPositiveColor("#aaaa00", "#aaaa00"); + node->setNegativeColor("#aa00aa", "#aa00aa"); cmdNodePool.append(node); } return node; @@ -368,8 +381,8 @@ void MixerCurveWidget::setCurve(const QList* points) node->setPos(w*i, h - (val*h)); node->verticalMove(true); - node->setPositiveColor(posColor0, posColor1); - node->setNegativeColor(negColor0, negColor1); +// node->setPositiveColor(posColor0, posColor1); +// node->setNegativeColor(negColor0, negColor1); node->update(); } @@ -407,10 +420,19 @@ void MixerCurveWidget::resizeCommands() QRectF rect = plot->boundingRect(); Node* node; - for (int i = 0; i<6; i++) { + node = getCommandNode(0); + + //centered under widget + node->setPos((rect.left() + rect.width() / 2) - 5, rect.height() + 10); + + for (int i = 1; i<6; i++) { node = getCommandNode(i); - node->setPos((rect.left() + rect.width() / 2) - 60 + (i * 20), rect.height() + 10); + //centered under widget + //node->setPos((rect.left() + rect.width() / 2) - 60 + (i * 20), rect.height() + 10); + + //bottom right of widget + node->setPos(rect.right() - 120 + (i * 20), rect.bottomRight().x() - 14); } //curveminplus @@ -431,15 +453,15 @@ void MixerCurveWidget::resizeCommands() //stepplus node = getCommandNode(10); - node->setPos(rect.bottomRight().x() - 60, rect.bottomRight().y() + 8); + node->setPos(rect.bottomRight().x() - 38, rect.bottomRight().y() + 5); //stepminus node = getCommandNode(11); - node->setPos(rect.bottomRight().x() - 40, rect.bottomRight().y() + 8); + node->setPos(rect.bottomRight().x() - 38, rect.bottomRight().y() + 15); //step node = getCommandNode(12); - node->setPos(rect.bottomRight().x() - 20, rect.bottomRight().y() + 8); + node->setPos(rect.bottomRight().x() - 20, rect.bottomRight().y() + 9); } void MixerCurveWidget::itemMoved(double itemValue) From 2be7721a0f51910dfc537046eea592819774f157 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Thu, 12 Jul 2012 12:40:51 -0700 Subject: [PATCH 037/543] MixerCurve, Commands on/off button. --- .../uavobjectwidgetutils/mixercurvepoint.h | 4 +- .../uavobjectwidgetutils/mixercurvewidget.cpp | 49 +++++++++++++++---- .../uavobjectwidgetutils/mixercurvewidget.h | 2 + 3 files changed, 45 insertions(+), 10 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h index 1747f1679..65b6b7955 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h @@ -57,7 +57,9 @@ public: void commandText(QString text); int getCommandIndex() { return index; } void setCommandIndex(int idx) { index = idx; } - void setActive(bool enable) { cmdActive = enable; } + + bool getCommandActive() { return cmdActive; } + void setCommandActive(bool enable) { cmdActive = enable; } void setToggle(bool enable) { cmdToggle = enable; } bool getToggle() { return cmdToggle; } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index 04464d9d8..fa56ebd33 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -187,6 +187,15 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) node->setNegativeColor("#0000aa", "#0000aa"); scene->addItem(node); + // commands toggle + node = getCommandNode(13); + node->setName("Commands"); + node->setToolTip("Toggle Command Buttons On/Off"); + node->setToggle(true); + node->setPositiveColor("#00aa00", "#00aa00"); //greenish + node->setNegativeColor("#000000", "#000000"); + scene->addItem(node); + resizeCommands(); initNodes(MixerCurveWidget::NODE_NUMELEM); @@ -420,10 +429,13 @@ void MixerCurveWidget::resizeCommands() QRectF rect = plot->boundingRect(); Node* node; + //reset node = getCommandNode(0); + node->setPos((rect.left() + rect.width() / 2) - 10, rect.height() + 10); - //centered under widget - node->setPos((rect.left() + rect.width() / 2) - 5, rect.height() + 10); + //commands on/off + node = getCommandNode(13); + node->setPos((rect.left() + rect.width() / 2) + 10, rect.height() + 10); for (int i = 1; i<6; i++) { node = getCommandNode(i); @@ -527,23 +539,42 @@ void MixerCurveWidget::setCommandText(const QString& name, const QString& text) } void MixerCurveWidget::activateCommand(const QString& name) { - for (int i=0; isetActive(node->getName() == name); + node->setCommandActive(node->getName() == name); node->update(); } } +void MixerCurveWidget::showCommands(bool show) +{ + for (int i=1; ishow(); + else + node->hide(); + + node->update(); + } +} void MixerCurveWidget::cmdActivated(Node* node) { if (node->getToggle()) { - for (int i=0; isetActive(false); - n->update(); + if (node->getName() == "Commands") { + node->setCommandActive(!node->getCommandActive()); + showCommands(node->getCommandActive()); + } + else { + for (int i=1; isetCommandActive(false); + n->update(); + } + + node->setCommandActive(true); } - node->setActive(true); } node->update(); emit commandActivated(node); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h index 3747730a0..2e7b73adc 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h @@ -58,8 +58,10 @@ public: double getMax(); double setRange(double min, double max); + void cmdActivated(Node* node); void activateCommand(const QString& name); + void showCommands(bool show); Node* getCmdNode(const QString& name); void setCommandText(const QString& name, const QString& text); From 268b9415423d16a51bc5c61ed63227e7dc2ab426 Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Thu, 12 Jul 2012 22:23:37 -0700 Subject: [PATCH 038/543] UI changes to the GCS interface pages --- .../config/configstabilizationwidget.cpp | 1 + .../openpilotgcs/src/plugins/config/input.ui | 903 +++++++++--------- .../src/plugins/config/stabilization.ui | 60 +- 3 files changed, 436 insertions(+), 528 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 89d866274..0ee0875ab 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -44,6 +44,7 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa // To bring old style sheet back without adding it manually do this: // Alternatively apply a global stylesheet to the QGroupBox // setStyleSheet("QGroupBox {background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); border: 1px outset #999; border-radius: 3; }"); + setStyleSheet("QPushButton {\nborder: 1px outset #999;\nborder-radius: 5;\nbackground-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255));\n}\n\nQPushButton:pressed {\n\n border-style: inset;\n background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255));\n\n}\n\n\nQPushButton:hover {\n border: 1px outset #999; \nborder-color: rgb(83, 83, 83);\nborder-radius: 4;\n}"); autoLoadWidgets(); realtimeUpdates=new QTimer(this); diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index 561e0fe9f..ae1c13963 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -261,433 +261,186 @@ 0 0 - 100 - 30 + 638 + 801 - - - - 10 - 310 - 611 - 151 - - - - - - - Configure each stabilization mode for each axis - - - - - - Stabilized3 - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Roll - - - Qt::AlignCenter - - - - - - - - 102 - 0 - - - - Qt::StrongFocus - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Pitch - - - Qt::AlignCenter - - - - - - - Qt::StrongFocus - - - - - - - Qt::StrongFocus - - - - - - - Qt::StrongFocus - - - - - - - Stabilized1 - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Yaw - - - Qt::AlignCenter - - - - - - - Qt::StrongFocus - - - - - - - - 102 - 0 - - - - Qt::StrongFocus - - - - - - - Qt::StrongFocus - - - - - - - Qt::StrongFocus - - - - - - - Stabilized2 - - - Qt::AlignCenter - - - - - - - - 102 - 0 - - - - Qt::StrongFocus - - - - - - - - - 10 - 20 - 611 - 231 - - - - FlightMode Switch Positions - - - - false - - - - 100 - 140 - 151 - 26 - - - - Qt::StrongFocus - - - - - false - - - - 100 - 110 - 151 - 26 - - - - Qt::StrongFocus - - - Select the stabilization mode on this position (manual/stabilized/auto) - - - - - - 10 - 115 - 62 - 17 - - - - Pos. 4 - - - - - false - - - - 100 - 170 - 151 - 26 - - - - Qt::StrongFocus - - - - - - 10 - 145 - 62 - 17 - - - - Pos. 5 - - - - - - 10 - 175 - 62 - 17 - - - - Pos. 6 - - - - - false - - - - 70 - 28 - 20 - 160 - - - - Qt::StrongFocus - - - This slider moves when you move the flight mode switch + + + + + FlightMode Switch Positions + + + + + + + + + + Pos. 1 + + + + + + + Pos. 2 + + + + + + + Pos. 3 + + + + + + + Pos. 4 + + + + + + + Pos. 5 + + + + + + + Pos. 6 + + + + + + + + + false + + + Qt::StrongFocus + + + This slider moves when you move the flight mode switch on your remote. It shows currently active flight mode. Setup the flight mode channel on the RC Input tab if you have not done so already. - - - 0 - - - 5 - - - 10 - - - 0 - - - 0 - - - Qt::Vertical - - - true - - - QSlider::TicksBelow - - - 1 - - - - - - 100 - 50 - 151 - 26 - - - - Qt::StrongFocus - - - - - - 100 - 80 - 151 - 26 - - - - Qt::StrongFocus - - - - - - 100 - 20 - 151 - 26 - - - - Qt::StrongFocus - - - Select the stabilization mode on this position (manual/stabilized/auto) - - - - - - 11 - 55 - 62 - 17 - - - - Pos. 2 - - - - - - 11 - 25 - 62 - 17 - - - - Pos. 1 - - - - - - 11 - 85 - 62 - 17 - - - - Pos. 3 - - - - - - 458 - 20 - 61 - 20 - - - - Number of positions your FlightMode switch has. + + + 0 + + + 5 + + + 10 + + + 0 + + + 0 + + + Qt::Vertical + + + true + + + QSlider::TicksBelow + + + 1 + + + + + + + + + Qt::StrongFocus + + + Select the stabilization mode on this position (manual/stabilized/auto) + + + + + + + Qt::StrongFocus + + + + + + + Qt::StrongFocus + + + + + + + false + + + Qt::StrongFocus + + + Select the stabilization mode on this position (manual/stabilized/auto) + + + + + + + false + + + Qt::StrongFocus + + + + + + + false + + + Qt::StrongFocus + + + + + + + + + + + + + + + Number of flight modes: + + + + + + + Number of positions your FlightMode switch has. Default is 3. @@ -695,53 +448,261 @@ It will be 2 or 3 for most of setups, but it also can be up to 6. In that case you have to configure your radio mixers so the whole range from min to max is split into N equal intervals, and you may set arbitrary channel value for each flight mode. - - - 1 - - - 6 - - - 3 - - - - - - 277 - 22 - 171 - 16 - - - - Number of flight modes: - - - - - - 310 - 120 - 191 - 30 - - - - - 75 - true - - - - Avoid "Manual" for multirotors! - - - true - - - + + + 1 + + + 6 + + + 3 + + + + + + + + + + 75 + true + + + + Avoid "Manual" for multirotors! + + + true + + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 40 + 20 + + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 50 + + + + + + + + + + + Configure each stabilization mode for each axis + + + + + + Stabilized3 + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Roll + + + Qt::AlignCenter + + + + + + + + 102 + 0 + + + + Qt::StrongFocus + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Pitch + + + Qt::AlignCenter + + + + + + + Qt::StrongFocus + + + + + + + Qt::StrongFocus + + + + + + + Qt::StrongFocus + + + + + + + Stabilized1 + + + Qt::AlignCenter + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Yaw + + + Qt::AlignCenter + + + + + + + Qt::StrongFocus + + + + + + + + 102 + 0 + + + + Qt::StrongFocus + + + + + + + Qt::StrongFocus + + + + + + + Qt::StrongFocus + + + + + + + Stabilized2 + + + Qt::AlignCenter + + + + + + + + 102 + 0 + + + + Qt::StrongFocus + + + + + + + + + + Qt::Vertical + + + + 20 + 300 + + + + + @@ -774,8 +735,8 @@ channel value for each flight mode. 0 0 - 499 - 121 + 638 + 801 diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index b09ff05ca..8e8fd71cd 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -24239,25 +24239,7 @@ border-radius: 5; Useful if you have accidentally changed some settings. - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Reload Board Data @@ -24288,25 +24270,7 @@ border-radius: 4; Send settings to the board but do not save to the non-volatile memory - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Apply @@ -24336,25 +24300,7 @@ border-radius: 4; Send settings to the board and save to the non-volatile memory - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Save From d2c99fefafaf226f93a9bc196c863265b56f56a7 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 13 Jul 2012 13:44:56 -0700 Subject: [PATCH 039/543] MixerCurve, Popup Dialog Support. --- .../src/plugins/config/mixercurve.cpp | 28 ++++++++--- .../src/plugins/config/mixercurve.h | 1 + .../uavobjectwidgetutils/mixercurvewidget.cpp | 26 ++++++++--- .../uavobjectwidgetutils/popupwidget.cpp | 46 +++++++++++++++++++ .../uavobjectwidgetutils/popupwidget.h | 39 ++++++++++++++++ .../uavobjectwidgetutils.pro | 6 ++- 6 files changed, 132 insertions(+), 14 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp create mode 100644 ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 73593dca9..e5f73590c 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -41,6 +41,11 @@ MixerCurve::MixerCurve(QWidget *parent) : m_curve = m_mixerUI->CurveWidget; m_settings = m_mixerUI->CurveSettings; + + m_mixerUI->SettingsGroup->hide(); + m_mixerUI->ValuesGroup->hide(); + m_curve->showCommands(false); + // create our spin delegate m_spinDelegate = new DoubleSpinDelegate(); @@ -338,15 +343,26 @@ void MixerCurve::SettingsTableChanged() void MixerCurve::CommandActivated(Node* node) { - //m_mixerUI->GenerateCurve->hide(); - - m_mixerUI->SettingsGroup->hide(); - m_mixerUI->ValuesGroup->hide(); - QString name = (node) ? node->getName() : "Reset"; - if (name == "Reset") { + if (name == "Reset") { ResetCurve(); + m_curve->showCommands(false); + } + else if (name == "Commands") { + + } + else if (name == "Popup") { + m_mixerUI->SettingsGroup->show(); + m_mixerUI->ValuesGroup->show(); + + PopupWidget* popup = new PopupWidget(); + popup->setWidget(this); + popup->exec(); + + m_mixerUI->SettingsGroup->hide(); + m_mixerUI->ValuesGroup->hide(); + m_curve->showCommands(false); } else if (name == "Linear") { m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Linear")); diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.h b/ground/openpilotgcs/src/plugins/config/mixercurve.h index bd24c46a9..346c3792b 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.h +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.h @@ -36,6 +36,7 @@ #include "mixercurvewidget.h" #include "dblspindelegate.h" #include "uavobjectwidgetutils_global.h" +#include "uavobjectwidgetutils/popupwidget.h" namespace Ui { diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index fa56ebd33..ec6853468 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -196,6 +196,15 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) node->setNegativeColor("#000000", "#000000"); scene->addItem(node); + // popup + node = getCommandNode(14); + node->setName("Popup"); + node->setToolTip("Advanced Mode..."); + node->setToggle(false); + node->setPositiveColor("#ff0000", "#ff0000"); //red + node->setNegativeColor("#ff0000", "#ff0000"); + scene->addItem(node); + resizeCommands(); initNodes(MixerCurveWidget::NODE_NUMELEM); @@ -229,10 +238,11 @@ Node* MixerCurveWidget::getCommandNode(int index) node->setCommandIndex(index); node->setActive(false); node->setPositiveColor("#aaaa00", "#aaaa00"); - node->setNegativeColor("#aa00aa", "#aa00aa"); + node->setNegativeColor("#1c870b", "#116703"); cmdNodePool.append(node); } return node; + } Node* MixerCurveWidget::getNode(int index) @@ -429,13 +439,17 @@ void MixerCurveWidget::resizeCommands() QRectF rect = plot->boundingRect(); Node* node; + //popup + node = getCommandNode(14); + node->setPos((rect.left() + rect.width() / 2) - 20, rect.height() + 10); + //reset node = getCommandNode(0); - node->setPos((rect.left() + rect.width() / 2) - 10, rect.height() + 10); + node->setPos((rect.left() + rect.width() / 2) + 20, rect.height() + 10); //commands on/off node = getCommandNode(13); - node->setPos((rect.left() + rect.width() / 2) + 10, rect.height() + 10); + node->setPos((rect.left() + rect.width() / 2) + 40, rect.height() + 10); for (int i = 1; i<6; i++) { node = getCommandNode(i); @@ -539,7 +553,7 @@ void MixerCurveWidget::setCommandText(const QString& name, const QString& text) } void MixerCurveWidget::activateCommand(const QString& name) { - for (int i=1; isetCommandActive(node->getName() == name); node->update(); @@ -548,7 +562,7 @@ void MixerCurveWidget::activateCommand(const QString& name) void MixerCurveWidget::showCommands(bool show) { - for (int i=1; ishow(); @@ -566,7 +580,7 @@ void MixerCurveWidget::cmdActivated(Node* node) showCommands(node->getCommandActive()); } else { - for (int i=1; isetCommandActive(false); n->update(); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp new file mode 100644 index 000000000..2befd1d62 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp @@ -0,0 +1,46 @@ +#include "popupwidget.h" + +#include + +PopupWidget::PopupWidget(QWidget *parent) : + QDialog(parent) +{ + m_widget = 0; + + QVBoxLayout* mainLayout = new QVBoxLayout(); + + m_layout = new QHBoxLayout(); + mainLayout->addLayout(m_layout); + + QHBoxLayout* buttonLayout = new QHBoxLayout(); + + m_closeButton = new QPushButton(tr("Close")); + buttonLayout->addWidget(m_closeButton); + + mainLayout->addLayout(buttonLayout); + + setLayout(mainLayout); + + connect(m_closeButton,SIGNAL(clicked()), this, SLOT(closePopup())); +} + +void PopupWidget::setWidget(QWidget* widget) +{ + m_widget = widget; + m_widgetParent = widget->parentWidget(); + + m_layout->addWidget(m_widget); +} + + +void PopupWidget::closePopup() +{ + if (m_widget && m_widgetParent) { + if(QGroupBox * w =qobject_cast(m_widgetParent)) + { + w->layout()->addWidget(m_widget); + } + } + + close(); +} diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h new file mode 100644 index 000000000..dcf2fe50c --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h @@ -0,0 +1,39 @@ +#ifndef POPUPWIDGET_H +#define POPUPWIDGET_H + +#include +#include +#include + + +#include "uavobjectwidgetutils_global.h" + +namespace Ui { +class PopupWidget; +} + +class UAVOBJECTWIDGETUTILS_EXPORT PopupWidget : public QDialog +{ + Q_OBJECT +public: + explicit PopupWidget(QWidget *parent = 0); + + void setWidget(QWidget* widget); + QWidget* getWidget() { return m_widget; } + QHBoxLayout* getLayout() { return m_layout; } + +signals: + +public slots: + +private slots: + void closePopup(); + +private: + QHBoxLayout* m_layout; + QWidget* m_widget; + QWidget* m_widgetParent; + QPushButton* m_closeButton; +}; + +#endif // POPUPWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutils.pro b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutils.pro index 475526325..cedaed7c3 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutils.pro +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutils.pro @@ -10,13 +10,15 @@ HEADERS += uavobjectwidgetutils_global.h \ mixercurvewidget.h \ mixercurvepoint.h \ mixercurveline.h \ - smartsavebutton.h + smartsavebutton.h \ + popupwidget.h SOURCES += uavobjectwidgetutilsplugin.cpp \ configtaskwidget.cpp \ mixercurvewidget.cpp \ mixercurvepoint.cpp \ mixercurveline.cpp \ - smartsavebutton.cpp + smartsavebutton.cpp \ + popupwidget.cpp OTHER_FILES += UAVObjectWidgetUtils.pluginspec From cb66f5000a64028dc6e1c85bffccd1048a65b32b Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 13 Jul 2012 16:34:29 -0700 Subject: [PATCH 040/543] MixerCurve, add support for node background image. --- .../uavobjectwidgetutils/mixercurvepoint.cpp | 4 +- .../uavobjectwidgetutils/mixercurvepoint.h | 2 + .../uavobjectwidgetutils/mixercurvewidget.cpp | 71 ++++++++++++++++--- 3 files changed, 65 insertions(+), 12 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp index 856f44b56..c5813eba2 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp @@ -46,7 +46,7 @@ Node::Node(MixerCurveWidget *graphWidget) cmdActive = false; vertical = false; cmdNode = false; - cmdToggle = true; + cmdToggle = true; posColor0 = "#1c870b"; //greenish? posColor1 = "#116703"; //greenish? @@ -109,6 +109,8 @@ void Node::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWid painter->setBrush(gradient); painter->setPen(QPen(Qt::black, 0)); painter->drawEllipse(boundingRect()); + if (!image.isNull()) + painter->drawImage(boundingRect().adjusted(1,1,-1,-1), image); painter->setPen(QPen(Qt::white, 0)); if (cmdNode) { diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h index 65b6b7955..2e9f872a1 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h @@ -65,6 +65,7 @@ public: void setPositiveColor(QString color0 = "#00ff00", QString color1 = "#00ff00") { posColor0 = color0; posColor1 = color1; } void setNegativeColor(QString color0 = "#ff0000", QString color1 = "#ff0000") { negColor0 = color0; negColor1 = color1; } + void setImage(QImage img) { image = img; } QRectF boundingRect() const; QPainterPath shape() const; @@ -89,6 +90,7 @@ private: QString posColor1; QString negColor0; QString negColor1; + QImage image; bool vertical; QString cmdName; diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index ec6853468..50f0e2f90 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -92,35 +92,56 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) node = getCommandNode(1); node->setName("Linear"); node->setToolTip("Generate a Linear Curve"); - node->commandText("/"); + QImage img = QImage(":/core/images/curve_linear.png"); + if (!img.isNull()) + node->setImage(img); + else + node->commandText("/"); + scene->addItem(node); // log node = getCommandNode(2); node->setName("Log"); node->setToolTip("Generate a Logarithmic Curve"); - node->commandText("("); + img = QImage(":/core/images/curve_log.png"); + if (!img.isNull()) + node->setImage(img); + else + node->commandText("("); scene->addItem(node); // exp node = getCommandNode(3); node->setName("Exp"); node->setToolTip("Generate an Exponential Curve"); - node->commandText(")"); + img = QImage(":/core/images/curve_exp.png"); + if (!img.isNull()) + node->setImage(img); + else + node->commandText(")"); scene->addItem(node); // flat node = getCommandNode(4); node->setName("Flat"); node->setToolTip("Generate a Flat Curve"); - node->commandText("--"); + img = QImage(":/core/images/curve_flat.png"); + if (!img.isNull()) + node->setImage(img); + else + node->commandText("--"); scene->addItem(node); // step node = getCommandNode(5); node->setName("Step"); node->setToolTip("Generate a Stepped Curve"); - node->commandText("z"); + img = QImage(":/core/images/curve_step.png"); + if (!img.isNull()) + node->setImage(img); + else + node->commandText("z"); scene->addItem(node); @@ -128,55 +149,83 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) node = getCommandNode(6); node->setName("MinPlus"); node->setToolTip("Increase Curve Minimum"); + img = QImage(":/core/images/curve_plus.png"); + if (!img.isNull()) + node->setImage(img); + else + node->commandText("+"); node->setToggle(false); node->setPositiveColor("#00aa00", "#00aa00"); //green node->setNegativeColor("#00aa00", "#00aa00"); - node->commandText("+"); scene->addItem(node); node = getCommandNode(7); node->setName("MinMinus"); node->setToolTip("Decrease Curve Minimum"); + img = QImage(":/core/images/curve_minus.png"); + if (!img.isNull()) + node->setImage(img); + else + node->commandText("-"); + node->setToggle(false); node->setPositiveColor("#aa0000", "#aa0000"); //red node->setNegativeColor("#aa0000", "#aa0000"); - node->commandText("-"); scene->addItem(node); node = getCommandNode(8); node->setName("MaxPlus"); node->setToolTip("Increase Curve Maximum"); + img = QImage(":/core/images/curve_plus.png"); + if (!img.isNull()) + node->setImage(img); + else + node->commandText("+"); + node->setToggle(false); node->setPositiveColor("#00aa00", "#00aa00"); //green node->setNegativeColor("#00aa00", "#00aa00"); - node->commandText("+"); scene->addItem(node); node = getCommandNode(9); node->setName("MaxMinus"); node->setToolTip("Decrease Curve Maximum"); + img = QImage(":/core/images/curve_plus.png"); + if (!img.isNull()) + node->setImage(img); + else + node->commandText("-"); + node->setToggle(false); node->setPositiveColor("#aa0000", "#aa0000"); //red node->setNegativeColor("#aa0000", "#aa0000"); - node->commandText("-"); scene->addItem(node); node = getCommandNode(10); node->setName("StepPlus"); node->setToolTip("Increase Step/Power Value"); + img = QImage(":/core/images/curve_plus.png"); + if (!img.isNull()) + node->setImage(img); + else + node->commandText("+"); node->setToggle(false); node->setPositiveColor("#00aa00", "#00aa00"); //green node->setNegativeColor("#00aa00", "#00aa00"); - node->commandText("+"); scene->addItem(node); node = getCommandNode(11); node->setName("StepMinus"); node->setToolTip("Decrease Step/Power Value"); + img = QImage(":/core/images/curve_minus.png"); + if (!img.isNull()) + node->setImage(img); + else + node->commandText("-"); + node->setToggle(false); node->setPositiveColor("#aa0000", "#aa0000"); //red node->setNegativeColor("#aa0000", "#aa0000"); - node->commandText("-"); scene->addItem(node); node = getCommandNode(12); From 685fb4e1d4e230b1c2069e2cf9f7342b5288b809 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 13 Jul 2012 22:41:58 -0700 Subject: [PATCH 041/543] MixerCurve bugs and tweeks: don't popup if already a popup; enable drawing only text in nodes; trap close/done/accept/reject events as closePopup(); --- .../src/plugins/config/mixercurve.cpp | 38 +++++------ .../uavobjectwidgetutils/mixercurvepoint.cpp | 65 ++++++++++--------- .../uavobjectwidgetutils/mixercurvepoint.h | 4 ++ .../uavobjectwidgetutils/mixercurvewidget.cpp | 38 +++++++---- .../uavobjectwidgetutils/mixercurvewidget.h | 2 + .../uavobjectwidgetutils/popupwidget.cpp | 25 ++++++- .../uavobjectwidgetutils/popupwidget.h | 5 +- 7 files changed, 112 insertions(+), 65 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index e5f73590c..982abb70c 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -133,6 +133,13 @@ void MixerCurve::UpdateCurveUI() //get the user settings QString curveType = m_mixerUI->CurveType->currentText(); + m_curve->activateCommand(curveType); + bool cmdsActive = m_curve->isCommandActive("Commands"); + + m_curve->showCommand("StepPlus", cmdsActive && curveType != "Linear"); + m_curve->showCommand("StepMinus", cmdsActive && curveType != "Linear"); + m_curve->showCommand("StepValue", cmdsActive && curveType != "Linear"); + m_mixerUI->CurveStep->setMinimum(0.0); m_mixerUI->CurveStep->setMaximum(100.0); m_mixerUI->CurveStep->setSingleStep(1.00); @@ -147,6 +154,10 @@ void MixerCurve::UpdateCurveUI() if ( curveType.compare("Flat")==0) { + m_mixerUI->minLabel->setVisible(false); + m_mixerUI->CurveMin->setVisible(false); + m_mixerUI->stepLabel->setVisible(true); + m_mixerUI->CurveStep->setVisible(true); m_mixerUI->CurveStep->setMinimum(m_mixerUI->CurveMin->minimum()); m_mixerUI->CurveStep->setMaximum(m_mixerUI->CurveMax->maximum()); m_mixerUI->CurveStep->setSingleStep(0.01); @@ -352,17 +363,18 @@ void MixerCurve::CommandActivated(Node* node) else if (name == "Commands") { } - else if (name == "Popup") { + else if (name == "Popup" && !m_curve->isCommandActive("Popup")) { m_mixerUI->SettingsGroup->show(); m_mixerUI->ValuesGroup->show(); + m_curve->showCommand("Popup", false); PopupWidget* popup = new PopupWidget(); - popup->setWidget(this); - popup->exec(); + popup->popUp(this); m_mixerUI->SettingsGroup->hide(); m_mixerUI->ValuesGroup->hide(); m_curve->showCommands(false); + m_curve->showCommand("Popup", true); } else if (name == "Linear") { m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Linear")); @@ -412,24 +424,8 @@ void MixerCurve::CurveTypeChanged() void MixerCurve::CurveMinChanged(double value) { QList points = m_curve->getCurve(); - QString CurveType = m_mixerUI->CurveType->currentText(); - - if ( CurveType.compare("Flat")==0) { - // the min changed so redraw the curve - // but since the curve is flat make all points = value - // because we use curveMin for the flat value in ui - for (int i = 0; i < points.count(); i++) { - points.pop_back(); - points.push_front(value); - } - } - else { - // the min changed so redraw the curve - // mixercurvewidget::setCurve will trim any points below min - - points.removeFirst(); - points.push_front(value); - } + points.removeFirst(); + points.push_front(value); setCurve(&points); } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp index c5813eba2..c7dfccf4f 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp @@ -47,6 +47,8 @@ Node::Node(MixerCurveWidget *graphWidget) vertical = false; cmdNode = false; cmdToggle = true; + drawNode = true; + drawText = true; posColor0 = "#1c870b"; //greenish? posColor1 = "#116703"; //greenish? @@ -81,43 +83,48 @@ QPainterPath Node::shape() const void Node::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *) { - QString text = cmdNode ? cmdText : QString().sprintf("% .2f", value()); + QString text = cmdNode ? cmdText : QString().sprintf("%.2f", value()); - QRadialGradient gradient(-3, -3, 10); - if (option->state & QStyle::State_Sunken) { - gradient.setCenter(3, 3); - gradient.setFocalPoint(3, 3); + if (drawNode) { + QRadialGradient gradient(-3, -3, 10); + if (option->state & QStyle::State_Sunken) { + gradient.setCenter(3, 3); + gradient.setFocalPoint(3, 3); - gradient.setColorAt(1, Qt::darkBlue); - gradient.setColorAt(0, Qt::darkBlue); - } else { - if (cmdNode) { - gradient.setColorAt(0, cmdActive ? posColor0 : negColor0); - gradient.setColorAt(1, cmdActive ? posColor1 : negColor1); - } - else { - if (value() < 0) { - gradient.setColorAt(0, negColor0); - gradient.setColorAt(1, negColor1); + gradient.setColorAt(1, Qt::darkBlue); + gradient.setColorAt(0, Qt::darkBlue); + } else { + if (cmdNode) { + gradient.setColorAt(0, cmdActive ? posColor0 : negColor0); + gradient.setColorAt(1, cmdActive ? posColor1 : negColor1); } else { - gradient.setColorAt(0, posColor0); - gradient.setColorAt(1, posColor1); + if (value() < 0) { + gradient.setColorAt(0, negColor0); + gradient.setColorAt(1, negColor1); + } + else { + gradient.setColorAt(0, posColor0); + gradient.setColorAt(1, posColor1); + } } } - } - painter->setBrush(gradient); - painter->setPen(QPen(Qt::black, 0)); - painter->drawEllipse(boundingRect()); - if (!image.isNull()) - painter->drawImage(boundingRect().adjusted(1,1,-1,-1), image); + painter->setBrush(gradient); + painter->setPen(QPen(Qt::black, 0)); + painter->drawEllipse(boundingRect()); - painter->setPen(QPen(Qt::white, 0)); - if (cmdNode) { - painter->drawText(0,4,text); + if (!image.isNull()) + painter->drawImage(boundingRect().adjusted(1,1,-1,-1), image); } - else { - painter->drawText(-13, 4, text); + + if (drawText) { + painter->setPen(QPen(drawNode ? Qt::white : Qt::black, 0)); + if (cmdNode) { + painter->drawText(0,4,text); + } + else { + painter->drawText(-13, 4, text); + } } } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h index 2e9f872a1..b2298c5bb 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h @@ -66,6 +66,8 @@ public: void setPositiveColor(QString color0 = "#00ff00", QString color1 = "#00ff00") { posColor0 = color0; posColor1 = color1; } void setNegativeColor(QString color0 = "#ff0000", QString color1 = "#ff0000") { negColor0 = color0; negColor1 = color1; } void setImage(QImage img) { image = img; } + void setDrawNode(bool draw) { drawNode = draw; } + void setDrawText(bool draw) { drawText = draw; } QRectF boundingRect() const; QPainterPath shape() const; @@ -98,6 +100,8 @@ private: bool cmdNode; bool cmdToggle; QString cmdText; + bool drawNode; + bool drawText; int index; }; diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp index 50f0e2f90..90a84f490 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.cpp @@ -230,6 +230,7 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) node = getCommandNode(12); node->setName("StepValue"); + node->setDrawNode(false); node->setToolTip("Current Step/Power Value"); node->setToggle(false); node->setPositiveColor("#0000aa", "#0000aa"); //blue @@ -249,6 +250,7 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent) node = getCommandNode(14); node->setName("Popup"); node->setToolTip("Advanced Mode..."); + node->commandText(""); node->setToggle(false); node->setPositiveColor("#ff0000", "#ff0000"); //red node->setNegativeColor("#ff0000", "#ff0000"); @@ -449,9 +451,6 @@ void MixerCurveWidget::setCurve(const QList* points) node->setPos(w*i, h - (val*h)); node->verticalMove(true); -// node->setPositiveColor(posColor0, posColor1); -// node->setNegativeColor(negColor0, negColor1); - node->update(); } curveUpdating = false; @@ -498,16 +497,13 @@ void MixerCurveWidget::resizeCommands() //commands on/off node = getCommandNode(13); - node->setPos((rect.left() + rect.width() / 2) + 40, rect.height() + 10); + node->setPos(rect.right() - 15, rect.bottomRight().x() - 14); for (int i = 1; i<6; i++) { node = getCommandNode(i); - //centered under widget - //node->setPos((rect.left() + rect.width() / 2) - 60 + (i * 20), rect.height() + 10); - //bottom right of widget - node->setPos(rect.right() - 120 + (i * 20), rect.bottomRight().x() - 14); + node->setPos(rect.right() - 130 + (i * 18), rect.bottomRight().x() - 14); } //curveminplus @@ -528,15 +524,15 @@ void MixerCurveWidget::resizeCommands() //stepplus node = getCommandNode(10); - node->setPos(rect.bottomRight().x() - 38, rect.bottomRight().y() + 5); + node->setPos(rect.bottomRight().x() - 40, rect.bottomRight().y() + 5); //stepminus node = getCommandNode(11); - node->setPos(rect.bottomRight().x() - 38, rect.bottomRight().y() + 15); + node->setPos(rect.bottomRight().x() - 40, rect.bottomRight().y() + 15); //step node = getCommandNode(12); - node->setPos(rect.bottomRight().x() - 20, rect.bottomRight().y() + 9); + node->setPos(rect.bottomRight().x() - 22, rect.bottomRight().y() + 9); } void MixerCurveWidget::itemMoved(double itemValue) @@ -609,6 +605,16 @@ void MixerCurveWidget::activateCommand(const QString& name) } } +void MixerCurveWidget::showCommand(const QString& name, bool show) +{ + Node* node = getCmdNode(name); + if (node) { + if (show) + node->show(); + else + node->hide(); + } +} void MixerCurveWidget::showCommands(bool show) { for (int i=1; iupdate(); } } +bool MixerCurveWidget::isCommandActive(const QString& name) +{ + bool active = false; + Node* node = getCmdNode(name); + if (node) { + active = node->getCommandActive(); + } + return active; +} + void MixerCurveWidget::cmdActivated(Node* node) { if (node->getToggle()) { diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h index 2e7b73adc..f2e8226cf 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvewidget.h @@ -61,6 +61,8 @@ public: void cmdActivated(Node* node); void activateCommand(const QString& name); + bool isCommandActive(const QString& name); + void showCommand(const QString& name, bool show); void showCommands(bool show); Node* getCmdNode(const QString& name); void setCommandText(const QString& name, const QString& text); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp index 2befd1d62..ca1af389b 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp @@ -21,7 +21,15 @@ PopupWidget::PopupWidget(QWidget *parent) : setLayout(mainLayout); - connect(m_closeButton,SIGNAL(clicked()), this, SLOT(closePopup())); + connect(m_closeButton,SIGNAL(clicked()), this, SLOT(close())); + connect(this, SIGNAL(accepted()),this,SLOT(close())); + connect(this,SIGNAL(rejected()), this, SLOT(close())); +} + +void PopupWidget::popUp(QWidget* widget) +{ + setWidget(widget); + exec(); } void PopupWidget::setWidget(QWidget* widget) @@ -32,6 +40,19 @@ void PopupWidget::setWidget(QWidget* widget) m_layout->addWidget(m_widget); } +bool PopupWidget::close() +{ + closePopup(); + + return QDialog::close(); +} + +void PopupWidget::done(int result) +{ + closePopup(); + + QDialog::done(result); +} void PopupWidget::closePopup() { @@ -41,6 +62,4 @@ void PopupWidget::closePopup() w->layout()->addWidget(m_widget); } } - - close(); } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h index dcf2fe50c..a19a6650c 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h @@ -18,6 +18,7 @@ class UAVOBJECTWIDGETUTILS_EXPORT PopupWidget : public QDialog public: explicit PopupWidget(QWidget *parent = 0); + void popUp(QWidget* widget = 0); void setWidget(QWidget* widget); QWidget* getWidget() { return m_widget; } QHBoxLayout* getLayout() { return m_layout; } @@ -25,7 +26,9 @@ public: signals: public slots: - + bool close(); + void done(int result); + private slots: void closePopup(); From 4a13554e1fc4a868d487cbc63bca9326a781bfac Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Sat, 14 Jul 2012 07:25:57 -0700 Subject: [PATCH 042/543] MixerCurve: disable command buttons; add conventional Reset/Advanced buttons; move min/max/step into SettingsGroup; --- .../src/plugins/config/mixercurve.cpp | 34 ++-- .../src/plugins/config/mixercurve.h | 1 + .../src/plugins/config/mixercurve.ui | 165 +++++++++--------- 3 files changed, 108 insertions(+), 92 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp index 982abb70c..4ad2e3afe 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.cpp +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.cpp @@ -43,8 +43,10 @@ MixerCurve::MixerCurve(QWidget *parent) : m_mixerUI->SettingsGroup->hide(); - m_mixerUI->ValuesGroup->hide(); m_curve->showCommands(false); + m_curve->showCommand("Reset", false); + m_curve->showCommand("Popup", false); + m_curve->showCommand("Commands", false); // create our spin delegate m_spinDelegate = new DoubleSpinDelegate(); @@ -62,6 +64,7 @@ MixerCurve::MixerCurve(QWidget *parent) : connect(m_mixerUI->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(CurveTypeChanged())); connect(m_mixerUI->ResetCurve, SIGNAL(clicked()), this, SLOT(ResetCurve())); + connect(m_mixerUI->PopupCurve, SIGNAL(clicked()),this,SLOT(PopupCurve())); connect(m_mixerUI->GenerateCurve, SIGNAL(clicked()), this, SLOT(GenerateCurve())); connect(m_curve, SIGNAL(curveUpdated()), this, SLOT(UpdateSettingsTable())); connect(m_curve, SIGNAL(commandActivated(Node*)),this, SLOT(CommandActivated(Node*))); @@ -128,6 +131,21 @@ void MixerCurve::ResetCurve() UpdateSettingsTable(); } +void MixerCurve::PopupCurve() +{ + if (!m_curve->isCommandActive("Popup")) { + + m_mixerUI->SettingsGroup->show(); + m_mixerUI->PopupCurve->hide(); + + PopupWidget* popup = new PopupWidget(); + popup->popUp(this); + + m_mixerUI->SettingsGroup->hide(); + m_mixerUI->PopupCurve->show(); + m_curve->showCommands(false); + } +} void MixerCurve::UpdateCurveUI() { //get the user settings @@ -363,18 +381,8 @@ void MixerCurve::CommandActivated(Node* node) else if (name == "Commands") { } - else if (name == "Popup" && !m_curve->isCommandActive("Popup")) { - m_mixerUI->SettingsGroup->show(); - m_mixerUI->ValuesGroup->show(); - m_curve->showCommand("Popup", false); - - PopupWidget* popup = new PopupWidget(); - popup->popUp(this); - - m_mixerUI->SettingsGroup->hide(); - m_mixerUI->ValuesGroup->hide(); - m_curve->showCommands(false); - m_curve->showCommand("Popup", true); + else if (name == "Popup" ) { + PopupCurve(); } else if (name == "Linear") { m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Linear")); diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.h b/ground/openpilotgcs/src/plugins/config/mixercurve.h index 346c3792b..1e60534f6 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.h +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.h @@ -79,6 +79,7 @@ protected: public slots: void ResetCurve(); + void PopupCurve(); void GenerateCurve(); void UpdateSettingsTable(); diff --git a/ground/openpilotgcs/src/plugins/config/mixercurve.ui b/ground/openpilotgcs/src/plugins/config/mixercurve.ui index 7adf707da..e59882d89 100644 --- a/ground/openpilotgcs/src/plugins/config/mixercurve.ui +++ b/ground/openpilotgcs/src/plugins/config/mixercurve.ui @@ -6,8 +6,8 @@ 0 0 - 441 - 334 + 543 + 467 @@ -183,79 +183,6 @@ - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - Reset - - - - - GenerateCurve - CurveSettings - ResetCurve - CurveType - verticalSpacer - - - - - - - 5 - 5 - - - - - 50 - 50 - - - - - 1000 - 1000 - - - - - 10 - 10 - - - - - 200 - 200 - - - - - 7 - - - - - - - - - - @@ -332,21 +259,101 @@ - + - Qt::Horizontal + Qt::Vertical - 40 - 20 + 20 + 40 + GenerateCurve + CurveSettings + CurveType + CurveMin + minLabel + CurveMax + maxLabel + CurveStep + stepLabel + verticalSpacer + + + + + 5 + 5 + + + + + 50 + 50 + + + + + 1000 + 1000 + + + + + 10 + 10 + + + + + 200 + 200 + + + + + 7 + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Reset + + + + + + + Advanced... + + + + + From d612f67b8d909a0071fd28e574bbf4f306f878f5 Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sat, 14 Jul 2012 11:50:17 -0700 Subject: [PATCH 043/543] more GUI changes and reorganizations --- .../openpilotgcs/src/plugins/config/input.ui | 556 +++++++++--------- .../openpilotgcs/src/plugins/config/output.ui | 448 ++++++++++++-- .../src/plugins/config/outputchannelform.cpp | 34 +- .../src/plugins/config/outputchannelform.ui | 326 ++-------- .../src/plugins/config/stabilization.ui | 14 +- .../openpilotgcs/src/plugins/config/txpid.ui | 8 +- 6 files changed, 758 insertions(+), 628 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index ae1c13963..0533913fa 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -6,17 +6,14 @@ 0 0 - 692 - 958 + 693 + 882 Form - - - 12 - + @@ -26,7 +23,7 @@ RC Input - + 12 @@ -49,183 +46,191 @@ 0 0 - 638 - 801 + 639 + 721 - - - - 0 + + + + + 0 + 0 + - - - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 5 - - - - - - - - - - Roll/Pitch/Yaw stick deadband - - - - - - - Stick deadband in percents of full range (0-10), zero to disable - - - 1 - - - 10.000000000000000 - - - 0.100000000000000 - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 5 - - - - - - - - Start Configuration Wizard - + + + + + + + + Start Configuration Wizard + + + + + + + Run Calibration + + + + + + + + + + + + + + + + 0 + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Preferred + + + + 20 + 5 + + + + + + + + + + Roll/Pitch/Yaw stick deadband + + + + + + + Stick deadband in percents of full range (0-10), zero to disable + + + 1 + + + 10.000000000000000 + + + 0.100000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + - - - - - Run Calibration - + + + + + + + 0 + 0 + + + + + 0 + 90 + + + + TextLabel + + + true + + + + + + + + + + + + + + + + + + + Back + + + + + + + Next + + + + + + + Cancel + + + + + + - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - 0 - 0 - - - - - 0 - 90 - - - - TextLabel - - - true - - - - - - - - - - - - - - - - - - - Back - - - - - - - Next - - - - - - - Cancel - - - - - - - + + + @@ -261,8 +266,8 @@ 0 0 - 638 - 801 + 624 + 776 @@ -712,7 +717,7 @@ margin:1px; Arming Settings - + 12 @@ -735,100 +740,109 @@ margin:1px; 0 0 - 638 - 801 + 639 + 721 - - - - - - 50 - false - - - - Arm airframe using throttle off and: - - - - - - - Qt::StrongFocus - - - Indicate the control used for arming the airframe, in addition to setting the throttle to its minimum position. In other terms "Throttle Off". - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - Arming timeout: - - - - - - - Qt::StrongFocus - - - After the time indicated here, the frame go back to disarmed state. - - - 64 - - - - - - - seconds. - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Airframe disarm is done by throttle off and opposite of above combination. + + + Arming Settings + + + + + + + + 50 + false + + + + Arm airframe using throttle off and: + + + + + + + Qt::StrongFocus + + + Indicate the control used for arming the airframe, in addition to setting the throttle to its minimum position. In other terms "Throttle Off". + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + Arming timeout: + + + + + + + Qt::StrongFocus + + + After the time indicated here, the frame go back to disarmed state. + + + 64 + + + + + + + seconds. + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + Airframe disarm is done by throttle off and opposite of above combination. + + + + @@ -1001,8 +1015,6 @@ border-radius: 4; fmsSsPos3Yaw tabWidget deadband - configurationWizard - runCalibration graphicsView wzBack wzNext diff --git a/ground/openpilotgcs/src/plugins/config/output.ui b/ground/openpilotgcs/src/plugins/config/output.ui index b2e8c9ca2..dc12661b6 100644 --- a/ground/openpilotgcs/src/plugins/config/output.ui +++ b/ground/openpilotgcs/src/plugins/config/output.ui @@ -6,17 +6,14 @@ 0 0 - 664 - 791 + 866 + 937 Form - - - 12 - + @@ -32,7 +29,7 @@ Output - + 12 @@ -55,13 +52,25 @@ 0 0 - 610 - 634 + 812 + 776 - + + + + 0 + 0 + + + + + 0 + 78 + + @@ -430,57 +439,376 @@ Leave at 50Hz for fixed wing. - - - 0 + + + - - QLayout::SetNoConstraint - - - - - - - - - - 519 - 0 - - - - Motors spin at neutral output when armed and throttle below zero (be careful) - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Vertical - - - - 20 - 458 - - - + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 14 + 20 + + + + + + + + + 0 + 0 + + + + + 22 + 0 + + + + + 75 + false + true + + + + Qt::LeftToRight + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font:bold; +margin:1px; + + + # + + + Qt::AlignCenter + + + 0 + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 1 + 20 + + + + + + + + + 0 + 0 + + + + + 104 + 0 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font:bold; +margin:1px; + + + Assignment + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 61 + 0 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font:bold; +margin:1px; + + + Min + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 185 + 0 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font:bold; +margin:1px; + + + Neutral (slowest for motor) + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 50 + 0 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font:bold; +margin:1px; + + + Max + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 40 + 0 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font:bold; +margin:1px; + + + Rev. + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 40 + 0 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font:bold; +margin:1px; + + + Link + + + Qt::AlignCenter + + + + + + + + + -1 + + + QLayout::SetDefaultConstraint + + + + + + + + + + 519 + 0 + + + + Motors spin at neutral output when armed and throttle below zero (be careful) + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + Qt::Vertical + + + + 20 + 542 + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp b/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp index f2d039edb..813c32a94 100644 --- a/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp @@ -35,23 +35,23 @@ OutputChannelForm::OutputChannelForm(const int index, QWidget *parent, const boo m_inChannelTest(false) { ui.setupUi(this); - if(!showLegend) - { - // Remove legend - QGridLayout *grid_layout = dynamic_cast(layout()); - Q_ASSERT(grid_layout); - for (int col = 0; col < grid_layout->columnCount(); col++) - { // remove every item in first row - QLayoutItem *item = grid_layout->itemAtPosition(0, col); - if (!item) continue; - // get widget from layout item - QWidget *legend_widget = item->widget(); - if (!legend_widget) continue; - // delete widget - grid_layout->removeWidget(legend_widget); - delete legend_widget; - } - } +// if(!showLegend) +// { +// // Remove legend +// QGridLayout *grid_layout = dynamic_cast(layout()); +// Q_ASSERT(grid_layout); +// for (int col = 0; col < grid_layout->columnCount(); col++) +// { // remove every item in first row +// QLayoutItem *item = grid_layout->itemAtPosition(0, col); +// if (!item) continue; +// // get widget from layout item +// QWidget *legend_widget = item->widget(); +// if (!legend_widget) continue; +// // delete widget +// grid_layout->removeWidget(legend_widget); +// delete legend_widget; +// } +// } // The convention for OP is Channel 1 to Channel 10. ui.actuatorNumber->setText(QString("%1:").arg(m_index+1)); diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.ui b/ground/openpilotgcs/src/plugins/config/outputchannelform.ui index 9c2c62f47..512e1bc4b 100644 --- a/ground/openpilotgcs/src/plugins/config/outputchannelform.ui +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.ui @@ -6,7 +6,7 @@ 0 0 - 813 + 645 58 @@ -20,53 +20,61 @@ 1 - - + + + + Qt::Horizontal + + + QSizePolicy::Minimum + + + + 5 + 20 + + + + + + - + 0 0 + + + 0 + 0 + + + + Qt::StrongFocus + + + 9999 + + + Qt::Horizontal + + + + + + + Qt::StrongFocus + - Current value of slider. + Maximum PWM value, beware of not overdriving your servo. - - 0000 + + 9999 - - - - - 0 - 0 - - - - - 75 - false - true - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font:bold; -margin:1px; - - - Link - - - Qt::AlignCenter - - - - + @@ -89,42 +97,6 @@ margin:1px; - - - - 0 - 0 - - - - - 75 - false - true - - - - Qt::LeftToRight - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font:bold; -margin:1px; - - - # - - - Qt::AlignCenter - - - 0 - - - - @@ -152,7 +124,7 @@ margin:1px; - + Qt::StrongFocus @@ -165,7 +137,7 @@ margin:1px; - + @@ -187,67 +159,7 @@ margin:1px; - - - - - 0 - 0 - - - - - 75 - false - true - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font:bold; -margin:1px; - - - Neutral (slowest for motor) - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 75 - false - true - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font:bold; -margin:1px; - - - Assignment - - - Qt::AlignCenter - - - - + Qt::Horizontal @@ -263,67 +175,7 @@ margin:1px; - - - - - 0 - 0 - - - - - 75 - false - true - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font:bold; -margin:1px; - - - Min - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 75 - false - true - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font:bold; -margin:1px; - - - Max - - - Qt::AlignCenter - - - - + @@ -345,87 +197,19 @@ margin:1px; - - - - Qt::Horizontal - - - QSizePolicy::Minimum - - - - 5 - 20 - - - - - - + + 0 0 - - - 75 - false - true - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font:bold; -margin:1px; + + Current value of slider. - Rev. - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - Qt::StrongFocus - - - 9999 - - - Qt::Horizontal - - - - - - - Qt::StrongFocus - - - Maximum PWM value, beware of not overdriving your servo. - - - 9999 + 0000 diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 8e8fd71cd..f51be1530 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,7 +6,7 @@ 0 0 - 786 + 757 993 @@ -509,7 +509,7 @@ 0 0 - 732 + 703 832 @@ -10587,7 +10587,7 @@ Attitude 0 0 - 717 + 470 923 @@ -23648,7 +23648,7 @@ border-radius: 5; 0 - 79 + 75 @@ -24199,7 +24199,7 @@ border-radius: 5; - 300 + 150 20 @@ -24315,14 +24315,14 @@ Useful if you have accidentally changed some settings. - + 0 0 - 136 + 300 20 diff --git a/ground/openpilotgcs/src/plugins/config/txpid.ui b/ground/openpilotgcs/src/plugins/config/txpid.ui index c10a16c6a..94ee7ae17 100644 --- a/ground/openpilotgcs/src/plugins/config/txpid.ui +++ b/ground/openpilotgcs/src/plugins/config/txpid.ui @@ -50,7 +50,7 @@ 0 0 654 - 671 + 659 @@ -583,6 +583,12 @@ margin:1px; 0 + + + 0 + 75 + + 16777215 From 27b53bf092615771360e526f6ec48aca563a4dfe Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sat, 14 Jul 2012 21:26:38 -0700 Subject: [PATCH 044/543] deleted the commented lines, tried resizing the margins and I couldnt get it to look quite right, so I ditched it. --- .../src/plugins/config/camerastabilization.ui | 32 +++++++++++++++---- .../src/plugins/config/outputchannelform.cpp | 17 ---------- 2 files changed, 25 insertions(+), 24 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index f935b6dcb..0f7b8f980 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -17,6 +17,9 @@ 12 + + 12 + @@ -33,13 +36,7 @@ 12 - - 12 - - - 12 - - + 12 @@ -90,6 +87,9 @@ + + 12 + @@ -131,6 +131,12 @@ false + + 12 + + + 12 + @@ -345,6 +351,12 @@ margin:1px; Advanced Settings (Control) + + 12 + + + 12 + @@ -756,6 +768,9 @@ value. Messages + + 12 + @@ -772,6 +787,9 @@ value. + + 12 + diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp b/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp index 813c32a94..0aaa900ab 100644 --- a/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp @@ -35,23 +35,6 @@ OutputChannelForm::OutputChannelForm(const int index, QWidget *parent, const boo m_inChannelTest(false) { ui.setupUi(this); -// if(!showLegend) -// { -// // Remove legend -// QGridLayout *grid_layout = dynamic_cast(layout()); -// Q_ASSERT(grid_layout); -// for (int col = 0; col < grid_layout->columnCount(); col++) -// { // remove every item in first row -// QLayoutItem *item = grid_layout->itemAtPosition(0, col); -// if (!item) continue; -// // get widget from layout item -// QWidget *legend_widget = item->widget(); -// if (!legend_widget) continue; -// // delete widget -// grid_layout->removeWidget(legend_widget); -// delete legend_widget; -// } -// } // The convention for OP is Channel 1 to Channel 10. ui.actuatorNumber->setText(QString("%1:").arg(m_index+1)); From a1593968f1ee00dea2d9e593de2eeaef28e1115d Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Mon, 16 Jul 2012 13:20:11 +0100 Subject: [PATCH 045/543] GCS-Changes uploader device pictures from SVG to some very nice looking PNGs. TODO-PNG for PIPX --- .../src/plugins/uploader/devicewidget.cpp | 42 ++++++++----------- .../src/plugins/uploader/devicewidget.h | 2 +- .../plugins/uploader/runningdevicewidget.cpp | 41 +++++++----------- .../plugins/uploader/runningdevicewidget.h | 2 +- .../src/plugins/uploader/uploader.qrc | 2 + 5 files changed, 37 insertions(+), 52 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp index e3ca707b3..c22e548b0 100644 --- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp @@ -31,7 +31,6 @@ deviceWidget::deviceWidget(QWidget *parent) : { myDevice = new Ui_deviceWidget(); myDevice->setupUi(this); - devicePic = NULL; // Initialize pointer to null // Initialization of the Device icon display myDevice->verticalGroupBox_loaded->setVisible(false); @@ -54,18 +53,14 @@ void deviceWidget::showEvent(QShowEvent *event) Q_UNUSED(event) // Thit fitInView method should only be called now, once the // widget is shown, otherwise it cannot compute its values and - // the result is usually a ahrsbargraph that is way too small. - if (devicePic) - { - myDevice->gVDevice->fitInView(devicePic,Qt::KeepAspectRatio); - } + // the result is usually a ahrsbargraph that is way too small + myDevice->gVDevice->fitInView(devicePic.rect(),Qt::KeepAspectRatio); } void deviceWidget::resizeEvent(QResizeEvent* event) { Q_UNUSED(event); - if (devicePic) - myDevice->gVDevice->fitInView(devicePic, Qt::KeepAspectRatio); + myDevice->gVDevice->fitInView(devicePic.rect(), Qt::KeepAspectRatio); } @@ -92,31 +87,28 @@ void deviceWidget::populate() myDevice->lblDevName->setText(deviceDescriptorStruct::idToBoardName(id)); myDevice->lblHWRev->setText(QString(tr("HW Revision: "))+QString::number(id & 0x00FF, 16)); - devicePic = new QGraphicsSvgItem(); - devicePic->setSharedRenderer(new QSvgRenderer()); switch (id) { case 0x0101: - devicePic->renderer()->load(QString(":/uploader/images/deviceID-0101.svg")); - break; - case 0x0301: - devicePic->renderer()->load(QString(":/uploader/images/deviceID-0301.svg")); - break; - case 0x0401: - devicePic->renderer()->load(QString(":/uploader/images/deviceID-0401.svg")); - break; - case 0x0402: - devicePic->renderer()->load(QString(":/uploader/images/deviceID-0402.svg")); + devicePic.load("");//TODO break; case 0x0201: - devicePic->renderer()->load(QString(":/uploader/images/deviceID-0201.svg")); + devicePic.load("");//TODO + break; + case 0x0301: + devicePic.load("");//TODO + break; + case 0x0401: + devicePic.load(":/uploader/images/gcs-board-cc.png"); + break; + case 0x0402: + devicePic.load(":/uploader/images/gcs-board-cc3d.png"); break; default: break; } - devicePic->setElementId("device"); - myDevice->gVDevice->scene()->addItem(devicePic); - myDevice->gVDevice->setSceneRect(devicePic->boundingRect()); - myDevice->gVDevice->fitInView(devicePic,Qt::KeepAspectRatio); + myDevice->gVDevice->scene()->addPixmap(devicePic); + myDevice->gVDevice->setSceneRect(devicePic.rect()); + myDevice->gVDevice->fitInView(devicePic.rect(),Qt::KeepAspectRatio); bool r = m_dfu->devices[deviceID].Readable; bool w = m_dfu->devices[deviceID].Writable; diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.h b/ground/openpilotgcs/src/plugins/uploader/devicewidget.h index 202023d50..d2eab8e28 100644 --- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.h +++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.h @@ -64,7 +64,7 @@ private: DFUObject *m_dfu; QByteArray downloadedFirmware; QString filename; - QGraphicsSvgItem *devicePic; + QPixmap devicePic; QByteArray descriptionArray; void status(QString str, StatusIcon ic); bool populateBoardStructuredDescription(QByteArray arr); diff --git a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp index 4bf17e615..354cc0702 100644 --- a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp @@ -32,15 +32,10 @@ runningDeviceWidget::runningDeviceWidget(QWidget *parent) : { myDevice = new Ui_runningDeviceWidget(); myDevice->setupUi(this); - devicePic = NULL; // Initialize pointer to null // Initialization of the Device icon display myDevice->devicePicture->setScene(new QGraphicsScene(this)); - /* - QPixmap pix = QPixmap(QString(":uploader/images/view-refresh.svg")); - myDevice->statusIcon->setPixmap(pix); - */ } @@ -50,15 +45,13 @@ void runningDeviceWidget::showEvent(QShowEvent *event) // Thit fitInView method should only be called now, once the // widget is shown, otherwise it cannot compute its values and // the result is usually a ahrsbargraph that is way too small. - if (devicePic) - myDevice->devicePicture->fitInView(devicePic,Qt::KeepAspectRatio); + myDevice->devicePicture->fitInView(devicePic.rect(),Qt::KeepAspectRatio); } void runningDeviceWidget::resizeEvent(QResizeEvent* event) { Q_UNUSED(event); - if (devicePic) - myDevice->devicePicture->fitInView(devicePic, Qt::KeepAspectRatio); + myDevice->devicePicture->fitInView(devicePic.rect(), Qt::KeepAspectRatio); } /** @@ -79,31 +72,29 @@ void runningDeviceWidget::populate() // DeviceID tells us what sort of HW we have detected: // display a nice icon: myDevice->devicePicture->scene()->clear(); - if (devicePic) - delete devicePic; - devicePic = new QGraphicsSvgItem(); - devicePic->setSharedRenderer(new QSvgRenderer()); switch (id) { case 0x0101: - devicePic->renderer()->load(QString(":/uploader/images/deviceID-0101.svg")); - break; - case 0x0301: - devicePic->renderer()->load(QString(":/uploader/images/deviceID-0301.svg")); - break; - case 0x0401: - devicePic->renderer()->load(QString(":/uploader/images/deviceID-0401.svg")); + devicePic.load("");//TODO break; case 0x0201: - devicePic->renderer()->load(QString(":/uploader/images/deviceID-0201.svg")); + devicePic.load("");//TODO + break; + case 0x0301: + devicePic.load("");//TODO + break; + case 0x0401: + devicePic.load(":/uploader/images/gcs-board-cc.png"); + break; + case 0x0402: + devicePic.load(":/uploader/images/gcs-board-cc3d.png"); break; default: break; } - devicePic->setElementId("device"); - myDevice->devicePicture->scene()->addItem(devicePic); - myDevice->devicePicture->setSceneRect(devicePic->boundingRect()); - myDevice->devicePicture->fitInView(devicePic,Qt::KeepAspectRatio); + myDevice->devicePicture->scene()->addPixmap(devicePic); + myDevice->devicePicture->setSceneRect(devicePic.rect()); + myDevice->devicePicture->fitInView(devicePic.rect(),Qt::KeepAspectRatio); QString serial = utilMngr->getBoardCPUSerial().toHex(); myDevice->CPUSerial->setText(serial); diff --git a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.h b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.h index 05dd7f0dc..58e9583c1 100644 --- a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.h +++ b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.h @@ -54,7 +54,7 @@ public: private: Ui_runningDeviceWidget *myDevice; int deviceID; - QGraphicsSvgItem *devicePic; + QPixmap devicePic; //void status(QString str, StatusIcon ic); diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader.qrc b/ground/openpilotgcs/src/plugins/uploader/uploader.qrc index 083eab94d..5cec90aac 100644 --- a/ground/openpilotgcs/src/plugins/uploader/uploader.qrc +++ b/ground/openpilotgcs/src/plugins/uploader/uploader.qrc @@ -13,5 +13,7 @@ images/warning.svg images/error.svg images/deviceID-0402.svg + images/gcs-board-cc.png + images/gcs-board-cc3d.png From faa7fafcbd6f96d670223b18f101881d7ffe1379 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 16 Jul 2012 13:08:12 -0700 Subject: [PATCH 046/543] MultiRotor Config, Bugfix: include TriYaw channel in getChannelDescriptions --- .../plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index 0b952a0be..59ff087ce 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -253,6 +253,8 @@ QStringList ConfigMultiRotorWidget::getChannelDescriptions() channelDesc[multi.VTOLMotorW-1] = QString("VTOLMotorW"); if (multi.VTOLMotorE > 0 && multi.VTOLMotorE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) channelDesc[multi.VTOLMotorE-1] = QString("VTOLMotorE"); + if (multi.TRIYaw > 0 && multi.TRIYaw <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) + channelDesc[multi.TRIYaw-1] = QString("Tri-Yaw"); return channelDesc; } From d8e685a226676956253e0187b935a6a66a54ed93 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 16 Jul 2012 13:30:36 -0700 Subject: [PATCH 047/543] MixerCurve, Tweek: adjust positive node text location. --- .../src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp index c7dfccf4f..f81d283d9 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.cpp @@ -123,7 +123,7 @@ void Node::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWid painter->drawText(0,4,text); } else { - painter->drawText(-13, 4, text); + painter->drawText( (value() < 0) ? -13 : -11, 4, text); } } } From ebe76e4ae65f7b4b94f705e7a418699936186494 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Tue, 17 Jul 2012 01:24:22 +0200 Subject: [PATCH 048/543] OP-39 Added some pages and some functionality to the OP SetupWizard. --- .../plugins/coreplugin/connectionmanager.cpp | 143 +++++------ .../plugins/coreplugin/connectionmanager.h | 32 ++- .../setupwizard/pages/abstractwizardpage.cpp | 35 +++ .../setupwizard/pages/abstractwizardpage.h | 48 ++++ .../setupwizard/pages/controllerpage.cpp | 225 ++++++++++++++++++ .../setupwizard/pages/controllerpage.h | 67 ++++++ .../setupwizard/pages/controllerpage.ui | 163 +++++++++++++ .../src/plugins/setupwizard/pages/endpage.cpp | 30 ++- .../src/plugins/setupwizard/pages/endpage.h | 33 ++- .../src/plugins/setupwizard/pages/endpage.ui | 2 +- .../setupwizard/pages/fixedwingpage.cpp | 42 ++++ .../plugins/setupwizard/pages/fixedwingpage.h | 49 ++++ .../setupwizard/pages/fixedwingpage.ui | 43 ++++ .../plugins/setupwizard/pages/helipage.cpp | 42 ++++ .../src/plugins/setupwizard/pages/helipage.h | 49 ++++ .../src/plugins/setupwizard/pages/helipage.ui | 43 ++++ .../plugins/setupwizard/pages/multipage.cpp | 125 ++++++++++ .../src/plugins/setupwizard/pages/multipage.h | 59 +++++ .../plugins/setupwizard/pages/multipage.ui | 146 ++++++++++++ .../pages/notyetimplementedpage.cpp | 42 ++++ .../setupwizard/pages/notyetimplementedpage.h | 49 ++++ .../pages/notyetimplementedpage.ui | 43 ++++ .../plugins/setupwizard/pages/startpage.cpp | 30 ++- .../src/plugins/setupwizard/pages/startpage.h | 32 ++- .../plugins/setupwizard/pages/surfacepage.cpp | 42 ++++ .../plugins/setupwizard/pages/surfacepage.h | 49 ++++ .../plugins/setupwizard/pages/surfacepage.ui | 43 ++++ .../plugins/setupwizard/pages/vehiclepage.cpp | 61 +++++ .../plugins/setupwizard/pages/vehiclepage.h | 50 ++++ .../plugins/setupwizard/pages/vehiclepage.ui | 168 +++++++++++++ .../src/plugins/setupwizard/setupwizard.cpp | 59 ++++- .../src/plugins/setupwizard/setupwizard.h | 20 +- .../src/plugins/setupwizard/setupwizard.pro | 36 ++- .../plugins/setupwizard/setupwizardplugin.cpp | 4 +- .../plugins/setupwizard/setupwizardplugin.h | 4 +- .../plugins/setupwizard/wizardResources.qrc | 3 + 36 files changed, 2002 insertions(+), 109 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.ui create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.ui create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.ui create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp index f49d98c0e..5fa2ead50 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp @@ -44,15 +44,15 @@ namespace Core { ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow, QTabWidget *modeStack) : - QWidget(mainWindow), // Pip - m_availableDevList(0), + QWidget(mainWindow), // Pip + m_availableDevList(0), m_connectBtn(0), - m_ioDev(NULL), - m_mainWindow(mainWindow) + m_ioDev(NULL), + m_mainWindow(mainWindow) { - // Q_UNUSED(mainWindow); + // Q_UNUSED(mainWindow); -/* QVBoxLayout *top = new QVBoxLayout; + /* QVBoxLayout *top = new QVBoxLayout; top->setSpacing(0); top->setMargin(0);*/ @@ -72,7 +72,7 @@ ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow, QTabWidge m_connectBtn->setEnabled(false); layout->addWidget(m_connectBtn); -/* Utils::StyledBar *bar = new Utils::StyledBar; + /* Utils::StyledBar *bar = new Utils::StyledBar; bar->setLayout(layout); top->addWidget(bar);*/ @@ -81,33 +81,29 @@ ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow, QTabWidge // modeStack->insertCornerWidget(modeStack->cornerWidgetCount()-1, this); modeStack->setCornerWidget(this, Qt::TopRightCorner); - QObject::connect(m_connectBtn, SIGNAL(pressed()), this, SLOT(onConnectPressed())); + QObject::connect(m_connectBtn, SIGNAL(pressed()), this, SLOT(onConnectPressed())); } ConnectionManager::~ConnectionManager() { - disconnectDevice(); // Pip - suspendPolling(); // Pip + disconnectDevice(); // Pip + suspendPolling(); // Pip } void ConnectionManager::init() { //register to the plugin manager so we can receive //new connection object from plugins - QObject::connect(ExtensionSystem::PluginManager::instance(), SIGNAL(objectAdded(QObject*)), this, SLOT(objectAdded(QObject*))); - QObject::connect(ExtensionSystem::PluginManager::instance(), SIGNAL(aboutToRemoveObject(QObject*)), this, SLOT(aboutToRemoveObject(QObject*))); + QObject::connect(ExtensionSystem::PluginManager::instance(), SIGNAL(objectAdded(QObject*)), this, SLOT(objectAdded(QObject*))); + QObject::connect(ExtensionSystem::PluginManager::instance(), SIGNAL(aboutToRemoveObject(QObject*)), this, SLOT(aboutToRemoveObject(QObject*))); } /** * Method called when the user clicks the "Connect" button */ -bool ConnectionManager::connectDevice() +bool ConnectionManager::connectDevice(devListItem device) { - devListItem connection_device = findDevice(m_availableDevList->itemData(m_availableDevList->currentIndex(),Qt::ToolTipRole).toString()); - if (!connection_device.connection) - return false; - - QIODevice *io_dev = connection_device.connection->openDevice(connection_device.Name); + QIODevice *io_dev = device.connection->openDevice(device.Name); if (!io_dev) return false; @@ -115,23 +111,23 @@ bool ConnectionManager::connectDevice() // check if opening the device worked if (!io_dev->isOpen()) { - qDebug() << "Error: io_dev->isOpen() returned FALSE .. could not open connection to " << connection_device.devName + qDebug() << "Error: io_dev->isOpen() returned FALSE .. could not open connection to " << device.devName << ": " << io_dev->errorString(); // close the device // EDOUARD: why do we close if we could not open ??? try { - connection_device.connection->closeDevice(connection_device.devName); + device.connection->closeDevice(device.devName); } catch (...) { // handle exception - qDebug() << "Exception: connection_device.connection->closeDevice(" << connection_device.devName << ")"; + qDebug() << "Exception: connection_device.connection->closeDevice(" << device.devName << ")"; } return false; } // we appear to have connected to the device OK // remember the connection/device details - m_connectionDevice = connection_device; + m_connectionDevice = device; m_ioDev = io_dev; connect(m_connectionDevice.connection, SIGNAL(destroyed(QObject *)), this, SLOT(onConnectionDestroyed(QObject *)), Qt::QueuedConnection); @@ -171,6 +167,8 @@ bool ConnectionManager::disconnectDevice() m_connectionDevice.connection = NULL; m_ioDev = NULL; + emit deviceDisconnected(); + m_connectBtn->setText("Connect"); m_availableDevList->setEnabled(true); @@ -184,7 +182,7 @@ void ConnectionManager::objectAdded(QObject *obj) { //Check if a plugin added a connection object to the pool IConnection *connection = Aggregation::query(obj); - if (!connection) return; + if (!connection) return; //qDebug() << "Connection object registered:" << connection->connectionName(); //qDebug() << connection->availableDevices(); @@ -196,23 +194,23 @@ void ConnectionManager::objectAdded(QObject *obj) // to do things m_connectionsList.append(connection); - QObject::connect(connection, SIGNAL(availableDevChanged(IConnection *)), this, SLOT(devChanged(IConnection *))); + QObject::connect(connection, SIGNAL(availableDevChanged(IConnection *)), this, SLOT(devChanged(IConnection *))); } void ConnectionManager::aboutToRemoveObject(QObject *obj) { //Check if a plugin added a connection object to the pool IConnection *connection = Aggregation::query(obj); - if (!connection) return; + if (!connection) return; - if (m_connectionDevice.connection && m_connectionDevice.connection == connection) // Pip - { // we are currently using the one that is about to be removed - m_connectionDevice.connection = NULL; - m_ioDev = NULL; - } + if (m_connectionDevice.connection && m_connectionDevice.connection == connection) // Pip + { // we are currently using the one that is about to be removed + m_connectionDevice.connection = NULL; + m_ioDev = NULL; + } - if (m_connectionsList.contains(connection)) - m_connectionsList.removeAt(m_connectionsList.indexOf(connection)); + if (m_connectionsList.contains(connection)) + m_connectionsList.removeAt(m_connectionsList.indexOf(connection)); } @@ -230,8 +228,11 @@ void ConnectionManager::onConnectPressed() { // Check if we have a ioDev already created: if (!m_ioDev) - { // connecting - connectDevice(); + { + // connecting to currently selected device + devListItem device = findDevice(m_availableDevList->itemData(m_availableDevList->currentIndex(), Qt::ToolTipRole).toString()); + if (device.connection) + connectDevice(device); } else { // disconnecting @@ -244,9 +245,9 @@ void ConnectionManager::onConnectPressed() */ devListItem ConnectionManager::findDevice(const QString &devName) { - foreach (devListItem d, m_devList) + foreach (devListItem d, m_devList) { - if (d.devName == devName) + if (d.devName == devName) return d; } @@ -264,13 +265,13 @@ devListItem ConnectionManager::findDevice(const QString &devName) */ void ConnectionManager::suspendPolling() { - foreach (IConnection *cnx, m_connectionsList) - { + foreach (IConnection *cnx, m_connectionsList) + { cnx->suspendPolling(); } - m_connectBtn->setEnabled(false); - m_availableDevList->setEnabled(false); + m_connectBtn->setEnabled(false); + m_availableDevList->setEnabled(false); } /** @@ -279,13 +280,13 @@ void ConnectionManager::suspendPolling() */ void ConnectionManager::resumePolling() { - foreach (IConnection *cnx, m_connectionsList) - { + foreach (IConnection *cnx, m_connectionsList) + { cnx->resumePolling(); } - m_connectBtn->setEnabled(true); - m_availableDevList->setEnabled(true); + m_connectBtn->setEnabled(true); + m_availableDevList->setEnabled(true); } /** @@ -294,21 +295,21 @@ void ConnectionManager::resumePolling() */ void ConnectionManager::unregisterAll(IConnection *connection) { - for (QLinkedList::iterator iter = m_devList.begin(); iter != m_devList.end(); ) - { - if (iter->connection == connection) - { - if (m_connectionDevice.connection && m_connectionDevice.connection == connection) - { // we are currently using the one we are about to erase - //onConnectionClosed(m_connectionDevice.connection); - disconnectDevice(); - } + for (QLinkedList::iterator iter = m_devList.begin(); iter != m_devList.end(); ) + { + if (iter->connection == connection) + { + if (m_connectionDevice.connection && m_connectionDevice.connection == connection) + { // we are currently using the one we are about to erase + //onConnectionClosed(m_connectionDevice.connection); + disconnectDevice(); + } - iter = m_devList.erase(iter); - } - else - ++iter; - } + iter = m_devList.erase(iter); + } + else + ++iter; + } } /** @@ -347,7 +348,7 @@ void ConnectionManager::devChanged(IConnection *connection) unregisterAll(connection); //and add them back in the list - QList availableDev = connection->availableDevices(); + QList availableDev = connection->availableDevices(); foreach (IConnection::device dev, availableDev) { QString cbName = connection->shortName() + ": " + dev.name; @@ -355,32 +356,35 @@ void ConnectionManager::devChanged(IConnection *connection) registerDevice(connection,cbName,dev.name,disp); } + qDebug() << "# devices " << m_devList.count(); + emit availableDevicesChanged(m_devList); + //add all the list again to the combobox - foreach (devListItem d, m_devList) + foreach (devListItem device, m_devList) { - m_availableDevList->addItem(d.displayName); - m_availableDevList->setItemData(m_availableDevList->count()-1,(const QString)d.devName,Qt::ToolTipRole); - if(!m_ioDev && d.displayName.startsWith("USB")) + m_availableDevList->addItem(device.displayName); + m_availableDevList->setItemData(m_availableDevList->count() - 1, (const QString)device.devName,Qt::ToolTipRole); + if(!m_ioDev && device.displayName.startsWith("USB")) { if(m_mainWindow->generalSettings()->autoConnect() || m_mainWindow->generalSettings()->autoSelect()) - m_availableDevList->setCurrentIndex(m_availableDevList->count()-1); + m_availableDevList->setCurrentIndex(m_availableDevList->count() - 1); + if(m_mainWindow->generalSettings()->autoConnect()) { - connectDevice(); - qDebug()<<"ConnectionManager::devChanged autoconnected USB device"; + connectDevice(device); + qDebug() << "ConnectionManager::devChanged autoconnected USB device"; } } } if(m_ioDev)//if a device is connected make it the one selected on the dropbox { - for(int x=0;xcount();++x) + for(int x=0; x < m_availableDevList->count(); ++x) { if(m_connectionDevice.devName==m_availableDevList->itemData(x,Qt::ToolTipRole).toString()) m_availableDevList->setCurrentIndex(x); } } - //disable connection button if the liNameif (m_availableDevList->count() > 0) if (m_availableDevList->count() > 0) m_connectBtn->setEnabled(true); @@ -388,7 +392,7 @@ void ConnectionManager::devChanged(IConnection *connection) m_connectBtn->setEnabled(false); } -} + void Core::ConnectionManager::connectionsCallBack() { @@ -398,4 +402,5 @@ void Core::ConnectionManager::connectionsCallBack() } connectionBackup.clear(); disconnect(ExtensionSystem::PluginManager::instance(),SIGNAL(pluginsLoadEnded()),this,SLOT(connectionsCallBack())); +} } //namespace Core diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h index 289e65590..4d57319ae 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h @@ -46,12 +46,12 @@ QT_END_NAMESPACE namespace Core { - class IConnection; +class IConnection; namespace Internal { - class FancyTabWidget; - class FancyActionBar; - class MainWindow; +class FancyTabWidget; +class FancyActionBar; +class MainWindow; } // namespace Internal @@ -75,19 +75,28 @@ public: void init(); QIODevice* getCurrentConnection() { return m_ioDev; } - devListItem getCurrentDevice() { return m_connectionDevice;} + devListItem getCurrentDevice() { return m_connectionDevice; } + devListItem findDevice(const QString &devName); + + QLinkedList getAvailableDevices() { return m_devList; } + + bool isConnected() { return m_ioDev != 0; } + + bool connectDevice(devListItem device); bool disconnectDevice(); + void suspendPolling(); void resumePolling(); protected: void unregisterAll(IConnection *connection); void registerDevice(IConnection *conn, const QString &devN, const QString &name, const QString &disp); - devListItem findDevice(const QString &devName); signals: void deviceConnected(QIODevice *dev); + void deviceDisconnected(); void deviceAboutToDisconnect(); + void availableDevicesChanged(const QLinkedList devices); private slots: void objectAdded(QObject *obj); @@ -96,9 +105,9 @@ private slots: void onConnectPressed(); void devChanged(IConnection *connection); -// void onConnectionClosed(QObject *obj); - void onConnectionDestroyed(QObject *obj); - void connectionsCallBack(); //used to call devChange after all the plugins are loaded + // void onConnectionClosed(QObject *obj); + void onConnectionDestroyed(QObject *obj); + void connectionsCallBack(); //used to call devChange after all the plugins are loaded protected: QComboBox *m_availableDevList; QPushButton *m_connectBtn; @@ -112,9 +121,8 @@ protected: QIODevice *m_ioDev; private: - bool connectDevice(); - Internal::MainWindow *m_mainWindow; - QList connectionBackup; + Internal::MainWindow *m_mainWindow; + QList connectionBackup; }; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.cpp new file mode 100644 index 000000000..31425fc34 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.cpp @@ -0,0 +1,35 @@ +/** + ****************************************************************************** + * + * @file abstractwizardpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup AbstractWizardPage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "abstractwizardpage.h" + +AbstractWizardPage::AbstractWizardPage(SetupWizard* wizard, QWidget *parent) : + QWizardPage(parent) +{ + m_wizard = wizard; + setFixedSize(600, 400); +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.h new file mode 100644 index 000000000..072d619e7 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.h @@ -0,0 +1,48 @@ +/** + ****************************************************************************** + * + * @file abstractwizardpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup AbstractWizardPage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef ABSTRACTWIZARDPAGE_H +#define ABSTRACTWIZARDPAGE_H + +#include +#include "setupwizard.h" + +class AbstractWizardPage : public QWizardPage +{ + Q_OBJECT +protected: + explicit AbstractWizardPage(SetupWizard *wizard, QWidget *parent = 0); + +private: + SetupWizard *m_wizard; + +public: + SetupWizard* getWizard() { return m_wizard; } + +}; + +#endif // ABSTRACTWIZARDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.cpp new file mode 100644 index 000000000..7d66957d9 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.cpp @@ -0,0 +1,225 @@ +/** + ****************************************************************************** + * + * @file controllerpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup ControllerPage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "controllerpage.h" +#include "ui_controllerpage.h" +#include "setupwizard.h" + +#include +#include + +ControllerPage::ControllerPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::ControllerPage) +{ + ui->setupUi(this); + + m_connectionManager = Core::ICore::instance()->connectionManager(); + Q_ASSERT(m_connectionManager); + connect(m_connectionManager, SIGNAL(availableDevicesChanged(QLinkedList)), this, SLOT(devicesChanged(QLinkedList))); + + connect(m_connectionManager, SIGNAL(deviceConnected(QIODevice*)), this, SLOT(connectionStatusChanged())); + connect(m_connectionManager, SIGNAL(deviceDisconnected()), this, SLOT(connectionStatusChanged())); + + connect(ui->manualCB, SIGNAL(toggled(bool)), this, SLOT(identificationModeChanged())); + connect(ui->connectButton, SIGNAL(clicked()), this, SLOT(connectDisconnect())); + + setupBoardTypes(); + setupDeviceList(); +} + +ControllerPage::~ControllerPage() +{ + delete ui; +} + +void ControllerPage::initializePage() +{ + if(anyControllerConnected()) { + SetupWizard::CONTROLLER_TYPE type = getControllerType(); + setControllerType(type); + } + else { + setControllerType(SetupWizard::CONTROLLER_UNKNOWN); + } + emit completeChanged(); +} + +bool ControllerPage::isComplete() const +{ + return (ui->manualCB->isChecked() && ui->boardTypeCombo->currentIndex() > 0) || + (!ui->manualCB->isChecked() && m_connectionManager->isConnected() && ui->boardTypeCombo->currentIndex() > 0); +} + +bool ControllerPage::validatePage() +{ + getWizard()->setControllerType((SetupWizard::CONTROLLER_TYPE)ui->boardTypeCombo->itemData(ui->boardTypeCombo->currentIndex()).toInt()); + return true; +} + +bool ControllerPage::anyControllerConnected() +{ + return m_connectionManager->isConnected(); +} + +SetupWizard::CONTROLLER_TYPE ControllerPage::getControllerType() +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectUtilManager* utilMngr = pm->getObject(); + int id = utilMngr->getBoardModel(); + + switch (id) { + case 0x0301: + return SetupWizard::CONTROLLER_PIPX; + case 0x0401: + return SetupWizard::CONTROLLER_CC; + case 0x0402: + return SetupWizard::CONTROLLER_CC3D; + case 0x0901: + return SetupWizard::CONTROLLER_REVO; + default: + return SetupWizard::CONTROLLER_UNKNOWN; + } +} + +void ControllerPage::setupDeviceList() +{ + devicesChanged(m_connectionManager->getAvailableDevices()); + connectionStatusChanged(); +} + +void ControllerPage::setupBoardTypes() +{ + QVariant v(0); + ui->boardTypeCombo->addItem("", SetupWizard::CONTROLLER_UNKNOWN); + ui->boardTypeCombo->addItem("OpenPilot CopterControl (CC)", SetupWizard::CONTROLLER_CC); + ui->boardTypeCombo->addItem("OpenPilot CopterControl (CC3D)", SetupWizard::CONTROLLER_CC3D); + ui->boardTypeCombo->addItem("OpenPilot Revolution", SetupWizard::CONTROLLER_REVO); + ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(ui->boardTypeCombo->count() - 1, 0), v, Qt::UserRole - 1); + ui->boardTypeCombo->addItem("OP PipX Modem", SetupWizard::CONTROLLER_PIPX); + ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(ui->boardTypeCombo->count() - 1, 0), v, Qt::UserRole - 1); +} + +void ControllerPage::setControllerType(SetupWizard::CONTROLLER_TYPE type) +{ + for(int i = 0; i < ui->boardTypeCombo->count(); ++i) { + if(ui->boardTypeCombo->itemData(i) == type) { + ui->boardTypeCombo->setCurrentIndex(i); + break; + } + } +} + +void ControllerPage::devicesChanged(QLinkedList devices) +{ + // Get the selected item before the update if any + QString currSelectedDeviceName = ui->deviceCombo->currentIndex() != -1 ? + ui->deviceCombo->itemData(ui->deviceCombo->currentIndex(), Qt::ToolTipRole).toString() : ""; + + // Clear the box + ui->deviceCombo->clear(); + + int indexOfSelectedItem = -1; + int i = 0; + + // Loop and fill the combo with items from connectionmanager + foreach (Core::devListItem device, devices) + { + ui->deviceCombo->addItem(device.displayName); + QString deviceName = (const QString)device.devName; + ui->deviceCombo->setItemData(ui->deviceCombo->count() - 1, deviceName, Qt::ToolTipRole); + if(currSelectedDeviceName != "" && currSelectedDeviceName == deviceName) { + indexOfSelectedItem = i; + } + i++; + } + + // Re select the item that was selected before if any + if(indexOfSelectedItem != -1) { + ui->deviceCombo->setCurrentIndex(indexOfSelectedItem); + } + connectionStatusChanged(); +} + +void ControllerPage::connectionStatusChanged() +{ + if(m_connectionManager->isConnected()) { + ui->deviceCombo->setEnabled(false); + ui->connectButton->setText(tr("Disconnect")); + ui->boardTypeCombo->setEnabled(false); + ui->manualCB->setEnabled(false); + QString connectedDeviceName = m_connectionManager->getCurrentDevice().devName; + for(int i = 0; i < ui->deviceCombo->count(); ++i) { + if(connectedDeviceName == ui->deviceCombo->itemData(i, Qt::ToolTipRole).toString()) { + ui->deviceCombo->setCurrentIndex(i); + break; + } + } + + SetupWizard::CONTROLLER_TYPE type = getControllerType(); + setControllerType(type); + } + else { + ui->deviceCombo->setEnabled(true); + ui->connectButton->setText(tr("Connect")); + ui->boardTypeCombo->setEnabled(false); + ui->manualCB->setEnabled(true); + ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(0, 0), QVariant(0), Qt::UserRole - 1); + setControllerType(SetupWizard::CONTROLLER_UNKNOWN); + } + emit completeChanged(); +} + +void ControllerPage::identificationModeChanged() +{ + if(ui->manualCB->isChecked()) { + ui->deviceCombo->setEnabled(false); + ui->boardTypeCombo->setEnabled(true); + ui->connectButton->setEnabled(false); + ui->boardTypeCombo->setCurrentIndex(1); + ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(0, 0), QVariant(0), Qt::UserRole - 1); + } + else { + ui->connectButton->setEnabled(ui->deviceCombo->count() > 0); + ui->deviceCombo->setEnabled(!m_connectionManager->isConnected()); + ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(0, 0), QVariant(1), Qt::UserRole - 1); + ui->boardTypeCombo->setCurrentIndex(0); + ui->boardTypeCombo->setEnabled(false); + } + emit completeChanged(); +} + +void ControllerPage::connectDisconnect() +{ + if(m_connectionManager->isConnected()) { + m_connectionManager->disconnectDevice(); + } + else { + m_connectionManager->connectDevice(m_connectionManager->findDevice(ui->deviceCombo->itemData(ui->deviceCombo->currentIndex(), Qt::ToolTipRole).toString())); + } + emit completeChanged(); +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.h new file mode 100644 index 000000000..b9b8ae111 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.h @@ -0,0 +1,67 @@ +/** + ****************************************************************************** + * + * @file controllerpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup ControllerPage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef CONTROLLERPAGE_H +#define CONTROLLERPAGE_H + +#include +#include +#include "setupwizard.h" +#include "abstractwizardpage.h" + +namespace Ui { +class ControllerPage; +} + +class ControllerPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit ControllerPage(SetupWizard *wizard, QWidget *parent = 0); + ~ControllerPage(); + void initializePage(); + bool isComplete() const; + bool validatePage(); + +private: + Ui::ControllerPage *ui; + bool anyControllerConnected(); + SetupWizard::CONTROLLER_TYPE getControllerType(); + void setupDeviceList(); + void setupBoardTypes(); + void setControllerType(SetupWizard::CONTROLLER_TYPE type); + Core::ConnectionManager *m_connectionManager; + +private slots: + void devicesChanged(QLinkedList devices); + void connectionStatusChanged(); + void identificationModeChanged(); + void connectDisconnect(); +}; + +#endif // CONTROLLERPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui new file mode 100644 index 000000000..a949d6a1d --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui @@ -0,0 +1,163 @@ + + + ControllerPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + 20 + 20 + 550 + 241 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot board identification</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">To continue we need to know what kind of OpenPilot board you want the wizard to create a configuration for. The wizard will try to automatically detect what type of board you have connected.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Please connect the board to a free usb port on your computer, or if a serial modem like BlueTooth, PipX or other is used, then power up the board and select the device to connect with from the list below. Then press Connect.</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">If the board already is connected and succesfully detected the board type will allready be displayed. You can disconnect and select another device if you need to detect another board.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">If your board isnt detected or if you want to create a configuration for a board that is not connected. Then select the Manual selection option below and select the board type from the drop down menu.</span></p></body></html> + + + Qt::AutoText + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + 20 + 270 + 560 + 110 + + + + + 8 + + + + OpenPilot board type + + + + false + + + + 150 + 70 + 260 + 22 + + + + + + + 150 + 30 + 260 + 22 + + + + + + + 434 + 70 + 111 + 23 + + + + Connect + + + + + + 441 + 33 + 101 + 17 + + + + Manual selection + + + + + + 20 + 32 + 121 + 16 + + + + + 75 + true + + + + Connection device: + + + + + + 20 + 72 + 131 + 16 + + + + + 75 + true + + + + Detected board type: + + + deviceCombo + connectButton + boardTypeCombo + manualCB + label_2 + label_3 + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp index 3270e23ff..dda55196e 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp @@ -1,8 +1,34 @@ +/** + ****************************************************************************** + * + * @file endpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup Setup Wizard Plugin + * @{ + * @brief A Wizard to make the initial setup easy for everyone. + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include "endpage.h" #include "ui_endpage.h" -EndPage::EndPage(QWidget *parent) : - QWizardPage(parent), +EndPage::EndPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), ui(new Ui::EndPage) { setFinalPage(true); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h index e4179e677..afbeb6177 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h @@ -1,18 +1,45 @@ +/** + ****************************************************************************** + * + * @file endpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + #ifndef ENDPAGE_H #define ENDPAGE_H -#include +#include "abstractwizardpage.h" namespace Ui { class EndPage; } -class EndPage : public QWizardPage +class EndPage : public AbstractWizardPage { Q_OBJECT public: - explicit EndPage(QWidget *parent = 0); + explicit EndPage(SetupWizard *wizard, QWidget *parent = 0); ~EndPage(); private: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui index cc0a5c162..f72b2d718 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui @@ -71,7 +71,7 @@ p, li { white-space: pre-wrap; } - Uppload configuration + Upload configuration diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp new file mode 100644 index 000000000..7295cc8a3 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -0,0 +1,42 @@ +/** + ****************************************************************************** + * + * @file fixedwingpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup FixedWingPage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "fixedwingpage.h" +#include "ui_fixedwingpage.h" + +FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::FixedWingPage) +{ + ui->setupUi(this); + setFinalPage(true); +} + +FixedWingPage::~FixedWingPage() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h new file mode 100644 index 000000000..697721a9e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h @@ -0,0 +1,49 @@ +/** + ****************************************************************************** + * + * @file fixedwingpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup FixedWingPage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef FIXEDWINGPAGE_H +#define FIXEDWINGPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class FixedWingPage; +} + +class FixedWingPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit FixedWingPage(SetupWizard *wizard, QWidget *parent = 0); + ~FixedWingPage(); + +private: + Ui::FixedWingPage *ui; +}; + +#endif // FIXEDWINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui new file mode 100644 index 000000000..0e4fde978 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui @@ -0,0 +1,43 @@ + + + FixedWingPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + 50 + 160 + 500 + 41 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">The fixed wing part the OpenPilot Setup Wizard is not yet implemented</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p></body></html> + + + Qt::AlignHCenter|Qt::AlignTop + + + true + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.cpp new file mode 100644 index 000000000..93bfc3503 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.cpp @@ -0,0 +1,42 @@ +/** + ****************************************************************************** + * + * @file helipage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup HeliPage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "helipage.h" +#include "ui_helipage.h" + +HeliPage::HeliPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::HeliPage) +{ + ui->setupUi(this); + setFinalPage(true); +} + +HeliPage::~HeliPage() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.h new file mode 100644 index 000000000..2b2b5b894 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.h @@ -0,0 +1,49 @@ +/** + ****************************************************************************** + * + * @file helipage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup HeliPage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef HELIPAGE_H +#define HELIPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class HeliPage; +} + +class HeliPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit HeliPage(SetupWizard *wizard, QWidget *parent = 0); + ~HeliPage(); + +private: + Ui::HeliPage *ui; +}; + +#endif // HELIPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.ui new file mode 100644 index 000000000..c3c6efd11 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.ui @@ -0,0 +1,43 @@ + + + HeliPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + 50 + 160 + 500 + 41 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">The helicopter part the OpenPilot Setup Wizard is not yet implemented</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p></body></html> + + + Qt::AlignHCenter|Qt::AlignTop + + + true + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp new file mode 100644 index 000000000..56ffa5fb0 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp @@ -0,0 +1,125 @@ +/** + ****************************************************************************** + * + * @file multipage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup MultiPage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "multipage.h" +#include "ui_multipage.h" +#include "setupwizard.h" + +MultiPage::MultiPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::MultiPage) +{ + ui->setupUi(this); + + QSvgRenderer *renderer = new QSvgRenderer(); + renderer->load(QString(":/configgadget/images/multirotor-shapes.svg")); + multiPic = new QGraphicsSvgItem(); + multiPic->setSharedRenderer(renderer); + QGraphicsScene *scene = new QGraphicsScene(this); + scene->addItem(multiPic); + ui->typeGraphicsView->setScene(scene); + + setupMultiTypesCombo(); + + // Default to Quad X since it is the most common setup + ui->typeCombo->setCurrentIndex(1); + connect(ui->typeCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateImageAndDescription())); +} + +MultiPage::~MultiPage() +{ + delete ui; +} + +void MultiPage::initializePage() +{ + updateImageAndDescription(); +} + +void MultiPage::setupMultiTypesCombo() +{ + ui->typeCombo->addItem("Tricopter", SetupWizard::MULTI_ROTOR_TRI_Y); + ui->typeCombo->addItem("Quadcopter X", SetupWizard::MULTI_ROTOR_QUAD_X); + ui->typeCombo->addItem("Quadcopter +", SetupWizard::MULTI_ROTOR_QUAD_PLUS); + ui->typeCombo->addItem("Hexacopter", SetupWizard::MULTI_ROTOR_HEXA); + ui->typeCombo->addItem("Hexacopter Coax", SetupWizard::MULTI_ROTOR_HEXA_COAX_Y); + ui->typeCombo->addItem("Hexacopter H", SetupWizard::MULTI_ROTOR_HEXA_H); + ui->typeCombo->addItem("Octocopter", SetupWizard::MULTI_ROTOR_OCTO); + ui->typeCombo->addItem("Octocopter Coax X", SetupWizard::MULTI_ROTOR_OCTO_COAX_X); + ui->typeCombo->addItem("Octocopter Coax +", SetupWizard::MULTI_ROTOR_OCTO_COAX_PLUS); + ui->typeCombo->addItem("Octocopter V", SetupWizard::MULTI_ROTOR_OCTO_V); +} + +void MultiPage::updateImageAndDescription() +{ + SetupWizard::MULTI_ROTOR_SUB_TYPE type = (SetupWizard::MULTI_ROTOR_SUB_TYPE) ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); + QString elementId = ""; + QString description = "Descriptive text with information about "; + description.append(ui->typeCombo->currentText()); + description.append(" multirotors."); + switch(type) + { + case SetupWizard::MULTI_ROTOR_TRI_Y: + elementId = "tri"; + break; + case SetupWizard::MULTI_ROTOR_QUAD_X: + elementId = "quad-x"; + break; + case SetupWizard::MULTI_ROTOR_QUAD_PLUS: + elementId = "quad-plus"; + break; + case SetupWizard::MULTI_ROTOR_HEXA: + elementId = "quad-hexa"; + break; + case SetupWizard::MULTI_ROTOR_HEXA_COAX_Y: + elementId = "hexa-coax"; + break; + case SetupWizard::MULTI_ROTOR_HEXA_H: + elementId = "quad-hexa-H"; + break; + case SetupWizard::MULTI_ROTOR_OCTO: + elementId = "quad-octo"; + break; + case SetupWizard::MULTI_ROTOR_OCTO_COAX_X: + elementId = "octo-coax-X"; + break; + case SetupWizard::MULTI_ROTOR_OCTO_COAX_PLUS: + elementId = "octo-coax-P"; + break; + case SetupWizard::MULTI_ROTOR_OCTO_V: + elementId = "quad-octo-v"; + break; + default: + elementId = ""; + break; + } + multiPic->setElementId(elementId); + ui->typeGraphicsView->setSceneRect(multiPic->boundingRect()); + ui->typeGraphicsView->fitInView(multiPic, Qt::KeepAspectRatio); + + ui->typeDescription->setText(description); +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h new file mode 100644 index 000000000..bc9f822ad --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h @@ -0,0 +1,59 @@ +/** + ****************************************************************************** + * + * @file multipage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup MultiPage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef MULTIPAGE_H +#define MULTIPAGE_H + +#include +#include + +#include "abstractwizardpage.h" + +namespace Ui { +class MultiPage; +} + +class MultiPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit MultiPage(SetupWizard *wizard, QWidget *parent = 0); + ~MultiPage(); + + void initializePage(); + +private: + Ui::MultiPage *ui; + void setupMultiTypesCombo(); + QGraphicsSvgItem *multiPic; + +private slots: + void updateImageAndDescription(); +}; + +#endif // MULTIPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui new file mode 100644 index 000000000..2c33fb4d5 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui @@ -0,0 +1,146 @@ + + + MultiPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + 20 + 20 + 541 + 151 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot multirotor configuration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This part of the wizard will set up the OpenPilot controller for use with a flying platform with multiple rotors. The wizard supports the most common types of multirotors. Other variants of multirotors can be configured by using custom configuration options in the configuration plugin in GCS.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Please select the type of multirotor you want to create a configuration for below:</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + 20 + 180 + 561 + 200 + + + + + 10 + + + + Multirotor type selection + + + + + 20 + 32 + 121 + 16 + + + + + 75 + true + + + + Multirotor type: + + + + + + 150 + 30 + 220 + 22 + + + + + + + 390 + 30 + 150 + 150 + + + + + 0 + 0 + + + + QFrame::NoFrame + + + 0 + + + 0 + + + Qt::ScrollBarAlwaysOff + + + Qt::ScrollBarAlwaysOff + + + false + + + + + + 20 + 69 + 351 + 111 + + + + Qt::ScrollBarAlwaysOn + + + Qt::ScrollBarAlwaysOff + + + Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.cpp new file mode 100644 index 000000000..57a43fda8 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.cpp @@ -0,0 +1,42 @@ +/** + ****************************************************************************** + * + * @file notyetimplementedpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup NotYetImplementedPage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "notyetimplementedpage.h" +#include "ui_notyetimplementedpage.h" + +NotYetImplementedPage::NotYetImplementedPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::NotYetImplementedPage) +{ + ui->setupUi(this); + setFinalPage(true); +} + +NotYetImplementedPage::~NotYetImplementedPage() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.h new file mode 100644 index 000000000..4f323d9fc --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.h @@ -0,0 +1,49 @@ +/** + ****************************************************************************** + * + * @file notyetimplementedpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup NotYetImplementedPage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef NOTYETIMPLEMENTEDPAGE_H +#define NOTYETIMPLEMENTEDPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class NotYetImplementedPage; +} + +class NotYetImplementedPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit NotYetImplementedPage(SetupWizard *wizard, QWidget *parent = 0); + ~NotYetImplementedPage(); + +private: + Ui::NotYetImplementedPage *ui; +}; + +#endif // NOTYETIMPLEMENTEDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.ui new file mode 100644 index 000000000..b5b54240d --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.ui @@ -0,0 +1,43 @@ + + + NotYetImplementedPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + 50 + 190 + 501 + 31 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">This part the OpenPilot Setup Wizard is not yet implemented</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp index f36631bb0..46110a9e4 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp @@ -1,8 +1,34 @@ +/** + ****************************************************************************** + * + * @file startpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup Setup Wizard Plugin + * @{ + * @brief A Wizard to make the initial setup easy for everyone. + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include "startpage.h" #include "ui_startpage.h" -StartPage::StartPage(QWidget *parent) : - QWizardPage(parent), +StartPage::StartPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), ui(new Ui::StartPage) { ui->setupUi(this); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h index f6cf9b6cd..3e9e120cc 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h @@ -1,18 +1,44 @@ +/** + ****************************************************************************** + * + * @file startpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup Setup Wizard Plugin + * @{ + * @brief A Wizard to make the initial setup easy for everyone. + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #ifndef STARTPAGE_H #define STARTPAGE_H -#include +#include "abstractwizardpage.h" namespace Ui { class StartPage; } -class StartPage : public QWizardPage +class StartPage : public AbstractWizardPage { Q_OBJECT public: - explicit StartPage(QWidget *parent = 0); + explicit StartPage(SetupWizard *wizard, QWidget *parent = 0); ~StartPage(); private: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.cpp new file mode 100644 index 000000000..a28724f2f --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.cpp @@ -0,0 +1,42 @@ +/** + ****************************************************************************** + * + * @file surfacepage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup SurfacePage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "surfacepage.h" +#include "ui_surfacepage.h" + +SurfacePage::SurfacePage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::SurfacePage) +{ + ui->setupUi(this); + setFinalPage(true); +} + +SurfacePage::~SurfacePage() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.h new file mode 100644 index 000000000..593aa1fca --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.h @@ -0,0 +1,49 @@ +/** + ****************************************************************************** + * + * @file surfacepage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup SurfacePage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef SURFACEPAGE_H +#define SURFACEPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class SurfacePage; +} + +class SurfacePage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit SurfacePage(SetupWizard *wizard, QWidget *parent = 0); + ~SurfacePage(); + +private: + Ui::SurfacePage *ui; +}; + +#endif // SURFACEPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.ui new file mode 100644 index 000000000..988bc300a --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.ui @@ -0,0 +1,43 @@ + + + SurfacePage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + 50 + 160 + 500 + 41 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">The surface vehicle part the OpenPilot Setup Wizard is not yet implemented</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p></body></html> + + + Qt::AlignHCenter|Qt::AlignTop + + + true + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp new file mode 100644 index 000000000..a616a1194 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp @@ -0,0 +1,61 @@ +/** + ****************************************************************************** + * + * @file vehiclepage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup VehiclePage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "vehiclepage.h" +#include "ui_vehiclepage.h" + +VehiclePage::VehiclePage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::VehiclePage) +{ + ui->setupUi(this); +} + +VehiclePage::~VehiclePage() +{ + delete ui; +} + +bool VehiclePage::validatePage() +{ + if(ui->multirotorButton->isChecked()) { + getWizard()->setVehicleType(SetupWizard::VEHICLE_MULTI); + } + else if(ui->fixedwingButton->isChecked()) { + getWizard()->setVehicleType(SetupWizard::VEHICLE_FIXEDWING); + } + else if(ui->heliButton->isChecked()) { + getWizard()->setVehicleType(SetupWizard::VEHICLE_HELI); + } + else if(ui->surfaceButton->isChecked()) { + getWizard()->setVehicleType(SetupWizard::VEHICLE_SURFACE); + } + else { + getWizard()->setVehicleType(SetupWizard::VEHICLE_UNKNOWN); + } + return true; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h new file mode 100644 index 000000000..5e72a3d21 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h @@ -0,0 +1,50 @@ +/** + ****************************************************************************** + * + * @file vehiclepage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup VehiclePage + * @{ + * @brief + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef VEHICLEPAGE_H +#define VEHICLEPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class VehiclePage; +} + +class VehiclePage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit VehiclePage(SetupWizard *wizard, QWidget *parent = 0); + ~VehiclePage(); + bool validatePage(); + +private: + Ui::VehiclePage *ui; +}; + +#endif // VEHICLEPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui new file mode 100644 index 000000000..fdc2d47d2 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui @@ -0,0 +1,168 @@ + + + VehiclePage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + 20 + 20 + 550 + 131 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Vehicle type selection</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">To continue the wizard needs to know what type of vehicle that the OpenPilot controller board is going to be used with. This step is cruicial since most of the following configuration is unique per vehicle type.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">So go ahead and select the type of vehicle you want to create a configuration for.</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + 20 + 200 + 561 + 181 + + + + + 0 + 0 + + + + Supported vehicle types + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + 50 + 40 + 100 + 100 + + + + Tricopter, Quadcopter, Hexacopter, Octocopter + + + Multirotor + + + true + + + true + + + true + + + false + + + + + + 170 + 40 + 100 + 100 + + + + Airplane, Sloper, Jet + + + Fixed wing + + + true + + + true + + + false + + + + + + 290 + 40 + 100 + 100 + + + + Helicopter + + + true + + + true + + + false + + + + + + 410 + 40 + 100 + 100 + + + + Car, Boat, U-Boat + + + Surface + + + true + + + true + + + false + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 26a5e386a..f11762bf6 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file setupwizard.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup Setup Wizard Plugin @@ -28,27 +28,72 @@ #include "setupwizard.h" #include "pages/startpage.h" #include "pages/endpage.h" +#include "pages/controllerpage.h" +#include "pages/vehiclepage.h" +#include "pages/multipage.h" +#include "pages/fixedwingpage.h" +#include "pages/helipage.h" +#include "pages/surfacepage.h" +#include "pages/notyetimplementedpage.h" SetupWizard::SetupWizard(QWidget *parent) : QWizard(parent) { setWindowTitle("OpenPilot Setup Wizard"); + m_controllerType = CONTROLLER_UNKNOWN; + m_vehicleType = VEHICLE_UNKNOWN; createPages(); } int SetupWizard::nextId() const { switch (currentId()) { - case PAGE_START: - return PAGE_END; - default: - return -1; + case PAGE_START: + return PAGE_CONTROLLER; + case PAGE_CONTROLLER: { + switch(getControllerType()) + { + case CONTROLLER_CC: + case CONTROLLER_CC3D: + return PAGE_VEHICLES; + default: + return PAGE_NOTYETIMPLEMENTED; + } + } + case PAGE_VEHICLES: { + switch(getVehicleType()) + { + case VEHICLE_FIXEDWING: + return PAGE_FIXEDWING; + case VEHICLE_HELI: + return PAGE_HELI; + case VEHICLE_SURFACE: + return PAGE_SURFACE; + case VEHICLE_MULTI: + return PAGE_MULTI; + default: + return PAGE_NOTYETIMPLEMENTED; + } + } + case PAGE_MULTI: + return PAGE_END; + case PAGE_NOTYETIMPLEMENTED: + return PAGE_END; + default: + return -1; } } void SetupWizard::createPages() { - setPage(PAGE_START, new StartPage()); - setPage(PAGE_END, new EndPage()); + setPage(PAGE_START, new StartPage(this)); + setPage(PAGE_CONTROLLER, new ControllerPage(this)); + setPage(PAGE_VEHICLES, new VehiclePage(this)); + setPage(PAGE_MULTI, new MultiPage(this)); + setPage(PAGE_FIXEDWING, new FixedWingPage(this)); + setPage(PAGE_HELI, new HeliPage(this)); + setPage(PAGE_SURFACE, new SurfacePage(this)); + setPage(PAGE_NOTYETIMPLEMENTED, new NotYetImplementedPage(this)); + setPage(PAGE_END, new EndPage(this)); setStartId(PAGE_START); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h index 42f75556a..34b20dd81 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file setupwizard.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup Setup Wizard Plugin @@ -37,9 +37,25 @@ class SetupWizard : public QWizard public: SetupWizard(QWidget *parent = 0); int nextId() const; + enum CONTROLLER_TYPE {CONTROLLER_UNKNOWN, CONTROLLER_CC, CONTROLLER_CC3D, CONTROLLER_REVO, CONTROLLER_PIPX}; + enum VEHICLE_TYPE {VEHICLE_UNKNOWN, VEHICLE_MULTI, VEHICLE_FIXEDWING, VEHICLE_HELI, VEHICLE_SURFACE}; + enum MULTI_ROTOR_SUB_TYPE {MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS, + MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, + MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS}; + + void setControllerType(SetupWizard::CONTROLLER_TYPE type) { m_controllerType = type; } + SetupWizard::CONTROLLER_TYPE getControllerType() const { return m_controllerType; } + + void setVehicleType(SetupWizard::VEHICLE_TYPE type) { m_vehicleType = type; } + SetupWizard::VEHICLE_TYPE getVehicleType() const { return m_vehicleType; } + private: - enum {PAGE_START, PAGE_END}; + enum {PAGE_START, PAGE_CONTROLLER, PAGE_VEHICLES, PAGE_MULTI, PAGE_FIXEDWING, + PAGE_HELI, PAGE_SURFACE, PAGE_NOTYETIMPLEMENTED, PAGE_END}; void createPages(); + + CONTROLLER_TYPE m_controllerType; + VEHICLE_TYPE m_vehicleType; }; #endif // SETUPWIZARD_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index 20d13155d..98ece1c83 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -1,21 +1,49 @@ TEMPLATE = lib TARGET = SetupWizard - +QT += svg + include(../../openpilotgcsplugin.pri) include(../../plugins/coreplugin/coreplugin.pri) +include(../../plugins/uavobjectutil/uavobjectutil.pri) HEADERS += setupwizardplugin.h \ setupwizard.h \ pages/startpage.h \ - pages/endpage.h + pages/endpage.h \ + pages/controllerpage.h \ + pages/vehiclepage.h \ + pages/notyetimplementedpage.h \ + pages/multipage.h \ + pages/fixedwingpage.h \ + pages/helipage.h \ + pages/surfacepage.h \ + pages/abstractwizardpage.h SOURCES += setupwizardplugin.cpp \ setupwizard.cpp \ pages/startpage.cpp \ - pages/endpage.cpp + pages/endpage.cpp \ + pages/controllerpage.cpp \ + pages/vehiclepage.cpp \ + pages/notyetimplementedpage.cpp \ + pages/multipage.cpp \ + pages/fixedwingpage.cpp \ + pages/helipage.cpp \ + pages/surfacepage.cpp \ + pages/abstractwizardpage.cpp OTHER_FILES += SetupWizard.pluginspec FORMS += \ pages/startpage.ui \ - pages/endpage.ui \ No newline at end of file + pages/endpage.ui \ + pages/controllerpage.ui \ + pages/vehiclepage.ui \ + pages/notyetimplementedpage.ui \ + pages/multipage.ui \ + pages/fixedwingpage.ui \ + pages/helipage.ui \ + pages/surfacepage.ui + +RESOURCES += \ + wizardResources.qrc diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp index a6dddbd4c..9f5b5c67b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp @@ -1,8 +1,8 @@ /** ****************************************************************************** * - * @file donothingplugin.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file setupwizardplugin.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup SetupWizardPlugin diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h index 4caecbcd0..96ca9e038 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h @@ -1,8 +1,8 @@ /** ****************************************************************************** * - * @file donothingplugin.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file setupwizardplugin.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup SetupWizardPlugin diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc new file mode 100644 index 000000000..1358ce976 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -0,0 +1,3 @@ + + + From 719a556b784f33bd70a8eefa5f413064cef7bd42 Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Tue, 17 Jul 2012 21:54:38 -0700 Subject: [PATCH 049/543] fixed the colos for all the forms so its not a topographic map greyscale look now, still converting the buttons all back to non style sheet --- .../src/plugins/config/airframe.ui | 190 +++++++++++++-- .../src/plugins/config/camerastabilization.ui | 85 ++++++- .../config/configstabilizationwidget.cpp | 3 +- .../openpilotgcs/src/plugins/config/input.ui | 229 ++++++++++++++++-- .../openpilotgcs/src/plugins/config/output.ui | 77 +++++- .../src/plugins/config/stabilization.ui | 210 +++++++++++++++- .../openpilotgcs/src/plugins/config/txpid.ui | 77 +++++- 7 files changed, 792 insertions(+), 79 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 0018812be..1221aae5d 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -6,7 +6,7 @@ 0 0 - 828 + 839 1007 @@ -28,10 +28,74 @@ - 12 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + QFrame::NoFrame @@ -43,8 +107,8 @@ 0 0 - 782 - 835 + 809 + 874 @@ -77,7 +141,7 @@ - 40 + 20 20 @@ -95,7 +159,7 @@ - 0 + 1 @@ -138,7 +202,7 @@ - 40 + 20 20 @@ -642,9 +706,12 @@ margin:1px; Qt::Horizontal + + QSizePolicy::MinimumExpanding + - 40 + 20 20 @@ -888,8 +955,8 @@ margin:1px; - 110 - 110 + 80 + 80 @@ -912,9 +979,12 @@ margin:1px; Qt::Horizontal + + QSizePolicy::MinimumExpanding + - 40 + 10 20 @@ -922,6 +992,12 @@ margin:1px; + + + 0 + 0 + + Throtte Curve @@ -952,8 +1028,8 @@ margin:1px; - 120 - 120 + 80 + 80 @@ -1339,9 +1415,12 @@ margin:1px; Qt::Horizontal + + QSizePolicy::MinimumExpanding + - 40 + 20 20 @@ -2513,17 +2592,75 @@ margin:1px; Advanced Settings - - 12 - - - 12 - - - 12 + + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + QFrame::NoFrame @@ -2535,8 +2672,8 @@ margin:1px; 0 0 - 249 - 303 + 809 + 874 @@ -2883,9 +3020,12 @@ p, li { white-space: pre-wrap; } Qt::Horizontal + + QSizePolicy::MinimumExpanding + - 40 + 20 20 diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index 0f7b8f980..b41aac015 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -13,6 +13,9 @@ Form + + false + 12 @@ -22,6 +25,9 @@ + + false + 0 @@ -29,6 +35,9 @@ Qt::ElideMiddle + + false + Camera Stabilization @@ -37,10 +46,74 @@ 12 - 12 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + false @@ -58,8 +131,8 @@ 0 0 - 766 - 622 + 790 + 646 @@ -764,6 +837,9 @@ value. + + false + Messages @@ -783,6 +859,9 @@ value. + + false + diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 0ee0875ab..319803ca8 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -44,7 +44,8 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa // To bring old style sheet back without adding it manually do this: // Alternatively apply a global stylesheet to the QGroupBox // setStyleSheet("QGroupBox {background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); border: 1px outset #999; border-radius: 3; }"); - setStyleSheet("QPushButton {\nborder: 1px outset #999;\nborder-radius: 5;\nbackground-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255));\n}\n\nQPushButton:pressed {\n\n border-style: inset;\n background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255));\n\n}\n\n\nQPushButton:hover {\n border: 1px outset #999; \nborder-color: rgb(83, 83, 83);\nborder-radius: 4;\n}"); + //setStyleSheet("QPushButton {\nborder: 1px outset #999;\nborder-radius: 5;\nbackground-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255));\n}\n\nQPushButton:pressed {\n\n border-style: inset;\n background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255));\n\n}\n\n\nQPushButton:hover {\n border: 1px outset #999; \nborder-color: rgb(83, 83, 83);\nborder-radius: 4;\n}"); + //setStyleSheet("background-color: rgb(230, 230, 230);"); autoLoadWidgets(); realtimeUpdates=new QTimer(this); diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index 0533913fa..a6532ed53 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -24,17 +24,78 @@ RC Input - + 12 - - 12 - - - 12 + + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + QFrame::NoFrame @@ -46,8 +107,8 @@ 0 0 - 639 - 721 + 663 + 745 @@ -244,17 +305,78 @@ Flight Mode Switch Settings - + 12 - - 12 - - - 12 + + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + QFrame::NoFrame @@ -266,7 +388,7 @@ 0 0 - 624 + 648 776 @@ -718,17 +840,78 @@ margin:1px; Arming Settings - + 12 - - 12 - - - 12 + + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + QFrame::NoFrame @@ -740,8 +923,8 @@ margin:1px; 0 0 - 639 - 721 + 663 + 745 diff --git a/ground/openpilotgcs/src/plugins/config/output.ui b/ground/openpilotgcs/src/plugins/config/output.ui index dc12661b6..a74281ab0 100644 --- a/ground/openpilotgcs/src/plugins/config/output.ui +++ b/ground/openpilotgcs/src/plugins/config/output.ui @@ -30,17 +30,78 @@ Output - + 12 - - 12 - - - 12 + + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + QFrame::NoFrame @@ -52,8 +113,8 @@ 0 0 - 812 - 776 + 836 + 800 diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index f51be1530..9aa5eb445 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,7 +6,7 @@ 0 0 - 757 + 786 993 @@ -493,8 +493,75 @@ 12 + + 0 + + + + + + + + 255 + 255 + 255 + + + + + + + 240 + 240 + 240 + + + + + + + + + 255 + 255 + 255 + + + + + + + 240 + 240 + 240 + + + + + + + + + 240 + 240 + 240 + + + + + + + 240 + 240 + 240 + + + + + + QFrame::NoFrame @@ -509,8 +576,8 @@ 0 0 - 703 - 832 + 756 + 856 @@ -10574,8 +10641,75 @@ Attitude 12 + + 0 + + + + + + + + 255 + 255 + 255 + + + + + + + 240 + 240 + 240 + + + + + + + + + 255 + 255 + 255 + + + + + + + 240 + 240 + 240 + + + + + + + + + 240 + 240 + 240 + + + + + + + 240 + 240 + 240 + + + + + + QFrame::NoFrame @@ -10587,7 +10721,7 @@ Attitude 0 0 - 470 + 741 923 @@ -23648,7 +23782,7 @@ border-radius: 5; 0 - 75 + 79 @@ -24199,7 +24333,7 @@ border-radius: 5; - 150 + 300 20 @@ -24239,7 +24373,25 @@ border-radius: 5; Useful if you have accidentally changed some settings. - + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } Reload Board Data @@ -24270,7 +24422,25 @@ Useful if you have accidentally changed some settings. Send settings to the board but do not save to the non-volatile memory - + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } Apply @@ -24300,7 +24470,25 @@ Useful if you have accidentally changed some settings. Send settings to the board and save to the non-volatile memory - + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } Save @@ -24315,14 +24503,14 @@ Useful if you have accidentally changed some settings. - + 0 0 - 300 + 136 20 diff --git a/ground/openpilotgcs/src/plugins/config/txpid.ui b/ground/openpilotgcs/src/plugins/config/txpid.ui index 94ee7ae17..45eb17a61 100644 --- a/ground/openpilotgcs/src/plugins/config/txpid.ui +++ b/ground/openpilotgcs/src/plugins/config/txpid.ui @@ -27,17 +27,78 @@ Tx PID - + 12 - - 12 - - - 12 + + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + QFrame::NoFrame @@ -49,8 +110,8 @@ 0 0 - 654 - 659 + 678 + 683 From ad260e98bbfb0a8799f638353c24adde8089688c Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 18 Jul 2012 12:10:54 +0100 Subject: [PATCH 050/543] GCS - Added PNGs, should have been part of previous commit. --- .../plugins/uploader/images/gcs-board-cc.png | Bin 0 -> 242450 bytes .../plugins/uploader/images/gcs-board-cc3d.png | Bin 0 -> 250010 bytes 2 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc.png create mode 100644 ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc3d.png diff --git a/ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc.png b/ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc.png new file mode 100644 index 0000000000000000000000000000000000000000..c4e77c025ae55fdd399254f01f7281e2d12ca328 GIT binary patch literal 242450 zcmYg%1yEbt_jPb@gL@mC6eoD0c#tB+-66OahvM#5oMJ%=6nA%r0>!O36f1=y#s2Ag z?>FCfXEK?|+_^dToPG9Md+l{1-zmx9VN+lO002BWSt(Tj09gj{;l)Hp{IXhRD1!LH za+1|?1psge|9+4Fnb~9j08*&6q~yDIR*vr-U9B9QKys3jASV|`n6;e+0N}X{|0-&$ zhC~*6zR{ubisH~X>>2ebkgAB7g5iLXO_%s20V-SY)+I|+VkX2#tw=zq+5O-hF==$O zz!BpIBynK9Ky!0ca8PuLKoJlq6k+Kt5Z-s^g6Yxf%ppQBt@n}~Y?wNp#^~H2|-HDTaQJnqs+XAMcDSMf^ zEvnBj@8CUNi#uGGE<|6Ioeh5v*f8Y#Ld9&{Ldu!x5dT@?nH&FBus^bS)=`sY;!uV9 zNUe0DExVp-{r7@`0xvX6HYeGx03DV;v^AZ9iji&0LScJSd_|eGY>~yqUldE#ZKpR@ ziYr}1&qI&h;yzHve#kZXfpzy>rf_2lTKHhV?bE)NdwI8_f1?Dm-P--c{Sct#$Y{7N zSk;t%%U#OkmLR@pbH0tnRG#fUb-wbH74IQBeDa~d_Y>ur=VkgVTk+XF5+#$1T-!R;QLF2f)i8nNo;xvj(igAcxAj(FvvyJn<| z1MJnhn#gi2WclKTbfOfoMbn-uovmY*a4e6ry9Z}F+QQm$pH^>g9_Y2OvZw(g3-=b( zd~oC<_qx4*y!!9u`71DD@`tk?V`x+L=WU(_TbPM6AJ83(6>;UZdJa9e^EvUq|6SgB zlly7;-0|2(TRVFf<9Ruij<&Y8u-r!XR36nsH;ZNN^_HdM?QesXat<1LfXvO#{{Dx@ z4*%AlM#rOwTV2deOia!VB;&5^3J2RhTz31n-Sl3qpb`|lLQbfqzxYWh>h){r@q1O; z}A)(qmesK*-h;t0!QtrC){?TBE&Nmrln7h*4_`yKzn@V&ny` zgBWNfIv9I!D}ED^d?b{@-~OrpKHLC|gY!1-@B4SMe6{|A;lgC?pO?>D-TpCeWe$Yo zf@y?Q1Lli|iyOQY$Ue8+J-7Wk zq)EVk^Dh0>L7?u7X#$r96J+eh*0O;3%Yh7&R5~0SoahovMyAyV30Yb0 z3}_^B(zlek^b8%8v9)iRHHbeGtVOK;&8b+)rhaLI#OHK?7z-b3q)cbw0Q^R&O_hYi zGR(D6E$8pBSSLBIPMtpMLS70Nhe?P0E)=Ufr21+%7{v*IE9k@`VNMj09lB^y*RnX8 zIK#AehkJW_x177G-E}Y5!^DO#k7W-|y+mb0v?PQ52v1mpA-RHY+bt z;*|uKo7BeDkp=Mp^hh*VayE^!Gr+1I&K#eEh}=5Mp5ET1e&nmjns0wV_jmrx8e-Ft8T75Hb6OCBioudIT(n7X^QDq^XEm;M+&W8S9Rz4j! zlkRm`%OlD4e#HhMaY9hKdtKhQi4c;I#N$#TTmRih)M9lsmekzrQT2N&vD?pSs=nKU(z@#Eoxdy8+nZ3B zS;s=hRzI)YjazX=z{&wG%G_)T=@I(`@v@#@!*SV@KXW1F#VlX$Ljkzy=kU_oJaEx@2a2nhQy;s&S1|qf7FkuyHI_ zpA#94NZLu)xklZT*ZD=`<6tgzYMR6lfXVa7w&~%)*z;!h>AmZX{o929c0%ueXH%fyi`-%hKPW}GqVfH7^EOR?#nz;bb;OOVpJN?Foth42dvrm3& z^BySJLWhBZ7PQd1Q@f{W{*#+`WG}sMOS%X|ji;&y)UX=$CjRaSu0i!^WUUz~r3iKG zq9}25qFi+(lTwm}Ki-G>jT;U^ZRt8iWruIg_#`dG0Z6P7)y)KcK6NWO4u#9spBKV| z*#%A@31UD(d|AlFw~)4{9LM!@57IN@qj3|5I^L6KTR+9W@!9^QpBlV3uX+E>#UM0DZ`!PMP|LdeyS~Qq>=_nZ=*5`+f#HQ~6Vf@%ukQ z4Ni^uZlU91Nk8nmFi{g=#ug{5P@j6e$(W;pzU3Gk6JP{4GKwjU*ci)s@#{JE4zbfx zb*pfYL=jIBNbSp*pXzu7p`n4U{L4nI^#4sO0Vd5e_3}BR3iVf_^dY5Il{ls-0NKE| zS6G>c^gy9NRW3}OXc3gyux>qvQZvruEi)t4bcfiG)R|dM0JnUKZ`;|Oqn7;I+}ZV$ zACa^_N&rjX>a%qFpb0T;IFd}daDlojx4=+Lp_1AunnK3gY8BUdK6|IkjP8)#x%abz zQaK-24a-OEb-AcamS<;(zG4FjfKp_*GkxLvGm=;Gb)KUg9*Ycrc^P(6K~972i3bxS zqeI!8jp(zyq{IR)Q%RtN*{RfX6EX?R$+|!g<~wj7e)r=VL4-0Tl890Y2;N?_WcR4i zw)Th$`lNFXaVZiU1DVR2EdQYaz&&gD1)30p8*0*7Q) z+Lki;fVIed((9%u_nH4|dRF|jftt3qW`Lw+0}exy6#Xjc=?28lwP6b!Ak$?In%h$e zA`j*i+>a@Q85oic*^OF7;SZ5Zngw8yg&nT02EFNAI&sMORW(oXwL)(1La|o)n_WSs zl?k{8X7?XA%grlA7ymhF)9?r9%h4%&BCVZ56!fPsGFBwBrnWXM4<#~Fnkg#>OA%O7 zD1>uaSQ#aN6HS?C$&JcABT{f%MrHh~e4jIF5xo=_2fN!8+jgm;n>&imQ72GV6%Q^z z7cEA0M7LjiQWoa{-v(}_*Xc7RALqo1(o~W&k=U1H{x71MuQ@laH&n~#K1j=Zkq6W< zO5aKflNxJ+0Kv=yBhs+~d^tulTqhQN2~#5>K&Ct!;-C5wN-^qud?6uRFq|YZ+_}De zm!GdKx#apG;y~lOk64(A-?KcjLqNz_vy)x*nGVY_9X>b>ep<&dre;)HSafrAQz=9t zoO^Td-OIcVRJMPqoM%w?MLVTU!*Z2i+{O4z{Oz%9V#~Bv*6^q_0ey;!EH_CZv7~H} zY78^_j$pgqXR=cCLUvw)!HCMbBno_B3ASyAD;+uMaoI`d&!9>@SV_4P1B$VJZCBXJ z*g%ec}BQ!GxlL5ksJGa?4R7t+_Kg#u_IOd$IRkh$h z;kK6MAQp9C*HlPU?T4HY6qWcQJCOtvfNeYwp$5W5QU=-XY=ndr1wvE1jjN%FuZwho zF@eDGuiswUeK=iG?y_IWGP+--?pkvgj+&=Y&je(f7SK75JYqX^`G^4!7GEt7K$Zf@L9C0C&f3L-koO_8zo@L1kOH~nRJ|__K7|Fw$64N?>oM}Ssg1Obw;>Ylned9AW5Z7US>#Bn12V0#_e|jUy~@Q~ zaNLBnwvO7tRZQfK5=2AtI?TIkMqYdP-Xnw{l*L`8|)x6}~vb@}zMlQ+!L(z7+ zRSPM3(8ttf60`RUG0s9PHC&kc-^%8#$8u7|l<;Fr`=j!CEJCK7zRjf`Os)gZTM{?$ zky=lG{AuK0tG+YRViCSw>GI!y{xY{OL7r*t-&!g9OcN84%G4`0H%v-${a+!GH z7I+(J#SCv$c_O+$#0F`W|L)w~-A!YGPg=P zC^?inbI~Fwkb>AIB*0bx;y^AyrjcCdhtqwe#irTHhwtScPdkuLZ+=HlP}nm(J4eV7 z@W;6>k;{+tXnH~B=gnQJ>A zg2{!SJTK<8o+hh|E>hEkJ@z_&gO)P;ZL|An*gHzE_BOn(ub!U0jro_0-Z+FH_?tu1 z3V)++B_;KcmwO~pj#dM6xGJ`FCdrHZduv~1GR>sB7#`9-lSlwfH&l?@D4s>81>APu zpgMX#h76(>jKUm70X6Vh@B=UlS-phHcjUm=^}3bUgwvPMp;{l71{7tbEN7aq=Ke?; zU3sn)?v-c)H(zHRNAK@;ZHI5nPYwul_P&;!8}kwWW_n2b%&PP_ALb1o>-usvY`rXkVq&1iOQ-$ zlWah09y3G-SBj+C)_9A~*(D9Sm0jq-?9a!;OWmY(*>lL`G4#7z+T<;?sgpU{Te}k# zbL%Ijn%KvflA!`zVT`k7u*MNw-0;IqI@f*J;Cj8erR7a&kdPIJS>+03u~TY zv90dPRk>}vtG82^^~J(-r+=ic7Z=JV636A50CUapJ4Icw`<1A|pZc-K<-l%*0$4mNU~+RSkc%o*o%2bVNn8A1^9Np7Q+ANG>sN z9FeVSv8jj!>w#lAd49|Yl(-sPTTH+%x;)y}Ua~(Gs3gyJa_9mQUZJx{>T2(1C=R~s ztj%0+S!&3%i$0l)suOuy-(kS2=7Tz-SI;O;F2!`%&$mG_3C7C7gb^@Cg9rtkqc7G% z-n6~>X6HS@LrG>=8fO2%-+&r{6ptQaV{0G?cT|MXhMZ~&3z%V+$MPxpR_9Wh##Vz? zKZiwTyCp8N*O=@x2a>O&Ci`8uK-^O@aEoH+;Wk@(BbI5^oNGcN zSAY{5HSC!kHVxh>{YiJ%`E+H|;BC%HcJKW-7TH**48HKy<;qaaF>#gab)qt@6f3tK zS<5o0ii~s3r`x0lYZD}zs=>bD3IGTLNwg-{9P9n~JV~2(ho6O!JQV^L+it*Hh| zLcSWjbr5xt;8@g(AK3mAILRLPw;UCV(oL1$O+#$<$~l|g3*4st7RWstJz`ngpQ867Ct(2PRVzg$i z<1qGY@EjLBs;2fcpJE)0@xB}j6)eN_)|Jm!Gq}6Ecc#VdGw)|7rq}DK5;3Lc_o^|k zPpP;1N60dJ;v@xHfNOR};v|}Xkf`N#H(`M^RL(eC{zIVtH%~ z3nkD0{9~o(B&39E313@RccA0>7uuNS;oE6D*>77EK!LEl*h)F2gwkoNd!zt*+`gxE zo6!g0AoGb3YEFUGZdy=+6*Tk5rVWQktu?Y*vX*pN5J)_ejP94ks7;^jr#kYxAOn}G zvq-;4?mH}iJXb*k4W1x$8BcS^%dvFM=FFLDKa<;^8Icw8X$oS8 zyUhaixg@$ao{s3{KF~Z#4}`ymmwudBl=i}d4caBSI97UiyQI*`C3WeXxW6O0V)2m;tv#gjY1`YFCLILaueSh0b~*z5D9&~ca++6qt>AL6fAWZ z3Y}ZaJgXWV-_BGNE}Y4>fWTc@4E#(XIJ|QO-n>AcdSumk09g>dEHDL`9w}Jd`({{> z(abUHH~YDtjSU_%OklF_@KfP{#0ZB|TLLwMu)OY^uMzrk&Msja0~{)6JAz(!JE}eh#C?NdBudZS^ly z){`lPL=O!#y>;G(m0dqSYWbW!)bKkFt)CEl6)A1TIKa&0MQm_=XJ7IX_Y<&7UJ&`DcgY%EfENp_PCckKw zcMM%WP|mv&GLF*cH#G3l%LTc&;nDPiM^$u0M!Q}xVNr^>XXBH| zmLSSvZ@d@a7y6QI9){Jt2Gp2hVbx1%TCjyqTQH&J^9Q8)-OO25QYi|wQDaQ-uq;?S zGH?<`M8Hwm-b9%nYf8R>Xy78tM)*=;?at7m}3Br-eenri=lcqVKd1uAJ7~7B=UqKDd#*D^)5#jY-buURsJEvM;L7Rx*g%zIl$6 zT~MHoqT+_85g21!sv=gHu=ixrEa;+MF4VS9D#6Mo1AC(fMGgTJq@VvxBr6xe+n}?; zySyvp-~7d8U-ZE`>05FGe2VToJ?mEy$S&!OI4Sl-`Lb zA(A6(=%A>h@Pb<+F^(PJ#K49 zh0K30&OhCCmdc6qPV7x)?{UqcmWFILi;~L~R9mhD%#G%lj7J=$10E?dP^?WGyguJxSGUS;QFAKbH4s%Z$6!0OR zj&*_Q_pCbQSh;GL-Fsks>%4KIv+V14#g}(hS;j>$S4dBnwaN=8yL)C`G zu*u{KMHsLSig<6ZOeY;97J(GDYcv;nesFR$m!_to+Zfw~PBbAXh95V8r%)&)AjKue zMzcJ9ZW`E;xWUYf@VNkkwwV&;UoQ zh>NV)nA7{==I6Al!r(ghi6Kiw0`s070hW5}>21xj*7dr-?8}-efqzww+~HD;e?^W9 z)lmbw7rnO+)V36uKHY9B0a~KTPKP9cnaaj!x2&?v`k zU%ikFaaxBLSc9k&$8`RaMuq!93{)VE@rK=6zZA~(J1`nhr6#Je?j>@7);ZBu> z>Lkv&Ey9yfgv=t+om!Y(gy6wUx<{eRQIFPzerG(^;b($+P4;KT*H?@-8d#MQJmnNx zM!Neer^mCss_&0lvI8O+UriMI=)4Fj%g9%g{M8+xsgMv-$kaQvoR&L4h&G>KZ(^c? z5PKHfg>t6&vnE8-R1LZLNP^SJFW!oLi#U&-qQ4iNO7lEL3nSZATZJeg$5QyZk+L88 zQ}far)6!cmhSb2oOAUO=!}%ilci%?1nJl^ zrZZAZ>1zyMuP}YqkREd$AFtE@t>XO+R#l(jUz`G_!=q!DpmA*|RfriyzY;)#2?e|d zfbnXaP-*6h3&-hwvi2#%x_=~y!2oO){qtweM2ZCp8tZ_=%NE);hWlf9WTXliU>ffkMRGi+Z!^y%I-FzqFP(RQ!6YKU?WlGMW! z>3uJ#-*{!;tkZRsAB<7cTpwc4=CRGozZ&4sgaiLpd=bMZnNaH+7>U4hnyCvz96%>i zCjD@Ai2``5;_fXF$kh6>b#gz&h>Wo}i^FnZjKs`*Ryx0e%c~-Mv?#R zkkbTJ!xcNer_MD8{~5P6()dzEXEip=vFi_K*IP^Z^>N$218r_a+aZ=$Xyb6ux=p=LWTsx|6Z}(mH6IKoZYb7vdPV8X>e&0Y1 z6zL!2}zLycVyVV85Tw_^xy7T!KY<)LUFJ2;l4@TJf?WQD)YjN(>$F z*e;>{SKlu~2wAAzEQz$e+MgR#u_s`JX+|Feg>s$|z|Sj32RwCa!(jJ(MroK?rWFN8TMt76_8=)3)%JNQz$Ssd?ArKYBK)cbraLuNl3l<{=b zHD`TmU95p`VUAv*xbzmgsOxb$jI&hrJ-I{@rW%V zc`p65>iI%96v@l<`;Y!r4d^IVyfIY~m$HGQZDU0sOeEaa7>B9!_KPkKFhVvuZav-2 zQQG%=`}QqAr>jS8Xyiy-lNx64y(%&dX5H+w5I}E)^MSU+1rFDXH$v^#{RCAG?$fXB z_YdvHPwC+*E%kgOD?pH`u>;M0fuDx%zXiHyVgWV0qG0b(cA5++V4gxI{)IFU^{3xU zeEL&6{n&ENw$jqJZYv4MzB~#b@AbFlee)>Cm+|yScwv10o^fkb1yhzpE`i1P1^#> z9tPJMoo5@MkaS#0CATeGtP)jCF9B+;?;Zka_x!MR_(67N+wnxvh%Ia!uY9 zGbrp7y+B(WHnJ^`6p8%D4~@2E^KiUzLL4YuwdU}&^y}9z%EpOd@&&@zzc@z_s2#$& zI}`UYB`Zc>J-Uo%lA1gVb8Nyy=roT$zxfoJ63)ydwT)V~aI`s`NVnKvOR7KA6IJm&_m5k%sXdwmhr~MoO~8i= zCnIQ-rbIU}t`;)N>_9BNTtcz6II^~Fkz9~X1NMTm(%TP{+j+Xk!#g-!l&MTOLGMEV zC=sa=pZgor%e(X{B~X6CQ+$e2^g@6>AwaKnwHJ7C@?xklL>v<^P=yiz!ru2jO%AK5 zW<-EMol)YC`kCe^@w=Bti_yB6^2TNiHn1SSw=1~d4 zK)+iLAD+KddA_Vw_TSuq)#Y`hecl#fQp({_PVlj8=xb?dIdAo2*==-Ezu?(xC;9xF z^n1bM5O6?JSa|AYa2kjs62_u<=UqXD96*Z}iu&cK*UbP`JfOjW)Z>M4gq~vuu}nO* zWP|FG>D&O&-#i&wPW&ZsQ#MxhVC_si$h_GsV}#IPRigYUkdMTH$z zT;nb<&|^U$vZQ=2Vz$)@c>}vQZ%uG5j6VODbmtQg{RHDm%{vY7?rywP)F}V9%P0@T z%*(BT6N?aEDOVV4!Hw(nYn)F3;j41*7uW|@QJ!Lg*KG2Mz#_C9$XvtDoFXEz8HeCz z)veRE)83}e-)z3ydK(fQ(_*_k{iO=4qdP?kdwhTXyqD$WoE?ps8LsoF-A@jSfR`1k z=X0t!)@$AhL9xuHl!E9+FpU0`iGS5d4Mm_?aie79uHO?h2ywd1?kMYyM ztQD4?q(#8O%*QH;9mt8^`GNGEGak}-$NH@oTNQk`h;=@1B(6>m$VE7eTWwK9o=BJk zLNx(0hR1zU59jy6S5j`?C?^Kh={O-wH}=rUjQmE|i+IHwI{f*Zw)3-ptwlHNLHk}C z2o>VPgmd=MSku~UVnM7rKH%WWJE9Lb<#$!*JV31V{brR)v(2FSOSIWg9Pzg33n5S7 z!}d@$uL~$2379nAm9*s4qo!qI>P;&3uE&Y9d*7jxeB)-1A0HKoQHVNXoFAeTGWfv1 zjcP57fA@Y=D}$8*T&PRaoP_LFk*qE;VoXqZY+!3G2j+!%#Po2n z6($}VVyp=Ti5OZW0*i>8gks@Egu^A>X!8{IrEdw#X1@G%Kps+{-FH2Hj>FA%9~6-k zg26?WNa$4wM@QAFkJvu1CNBRJDA$tHqO@ zF1AsA=mBUMx|8QRpENAid2keM2SipcpOEmMW4!bQmY0_!K!xz#JLs8MHUkaIJed>) zPGq>>T@y%^BK))+<$Bdalm{Y|6W8KwnPW?tm~rmV(B9vOpD08Prg-uy2((GSN9S#Y ze^v-I;amU2Db!YxoPtK-h7kuUBud59T5_Uh!j`M3W3Qh5l)x=VzzIFl>`P(Rh#D`K zlvT^Y%i+aVa1{HgZ!(Obq>TKFH%8TXh36gC_-^7S`!L~J`HYXPhsCosP2&-M zbDtNJU*Sy=ztar{;rx+6KB!{2ekq*v#_5d_MoaPamzV1g!5p4fAN?V(cMb3B$5@71 zZG+REwoCd}*u-o9+C#S50IH+q2v>xU?}oo*B&vNBQR+zFuTgA6*FL=FD{E!R!X>E! zqCXFBmQVQHj~4^`!k_oKt!*)~8({SZ5Ix&cw+Mq7J181EGjl3PUOGHbYzg$}`U6Bu z1Kx%(M$ww1Z@S&>w6Yha7{lo0YLyA(5fX* zBV5^&$!nb&`etveR6M$Tgw0k`YX9OlLMC!-c_ijoJ$Jl5#xz8Y!w)xbQ1@Di@3Pnr z58LcX^ZWJo9OWbEAGgLiQ7F*VAJLcE1!1l$N%g>Fr7 zs$LURLxJN8A{BwU#=bm4I52ez+0?LM8xvH?H`x^myi`$m+;QV&gi!9FdB!eT+dM-q zGfCBf@9L6}D0bfN^p0>zm6StVaZ{_WWi~0mck(pH&$#ADK)(`Rh0%d8xN8KTaZ+K0 zB%X3q(r59RDJywSMVU(S8B75MQ@=)}U=Bv!{%rpfYk1!N184m_jQUf>g1-FLi*!Q9 z`66D=+7pAHvyLmj^XUa|MyLGP1Wh-@StoBEZPL1Xw?@!tmvs>gp|8Kcf8kZ?sIqzg zK@99@wv4&uPvR2?T&iTQx8%)(weRD_Cm9~9kHoJ$bHh(onhKZfXcg5UPj79joi4M6uOjz_V-KjkqXjIs6B2m*o8d6fx+zdH~|>_G_Y`5b-|`E>kWPsK21xa zfi+&vZFNyzMeIxMm$}wLD?GS@BM-BkD5yw4C>NECsY~rgxOtZS&fN-SoWdfS_$#n} z3yqHeRl&*$GFjf*dr)1&QewPVkD$K7dgOz@JpC4(LCFq=@nlj3z z|8?5N_;F#0Q-fVaBj_9n9>s-A37)qc_=zWMj-JMK$#E0Wb%no@fo1%3$wT&tRpk zdk)=n!8~|Ab4S`{sf7J;=;izJ}Hb^lTVG#MPyBDWjPajy>**1@w*20*hzS{BeuU`M^6pT|V<=T!X z7Y#dCDEig-DsYJdk`>cak@#v-HH*BA5}?>*3`lIz4_bt z`dF73ut#0R88B&>DtLZA46_f|c~&@Q6BrU7SsZpo4rzi(j*iE)w9{KfY;Vc8A5Oo} zv&=>bWGYGLbvcBVPlNP;W?l@Be`Xlv7BZYh&?W=B)6%e!|47F64G|o#pNeA}n}B;H z!|5t2tXD6@p6IUF2L9SyqM2&6ckUi35n^N;^-zm>X)g7 z-`{Yac3vCuP~hEkK1JMpLcmvVzsM;T1(SG5@O~23(B!a6HfIVqZMG_QCX-4Tn$vEi z+pXBHix!ea3LPysDrn486+Q&jsf-$qnL5A|91|Fo)op2qie=hdhQ)~9SL*0{$x%ws z%O>+yD*>!fJG&uY9E>@?3A7NIaq{@5C9{QzWm3ScI59T`kWbv(wD(WnnSI7XeM5{* zvbe)lrXZ*qMT2J6uy0tigyR7lZDW_?)t7NfVsK%tbx7iqvP1 z?8C(EKKGN1$rGpFyqW8Ly@P|a;r24|yZw9pFGsX;Np7e=5|e6W;^%&@s@#^g7s*3} zH^gU*2B)_PzSQNuizB3i^Azg_90`$km{il!N0Jj3sDHHR*C`>%(l27x07?zgsed)- zQ%xrimfhZ3LsrF2WJCq?XqR}sq35yXIeM1+Fi!Hu>w@6)!#ndei@oNsO+d#w!hyn* zh3A=zK~rR1ut4EV%PEpi6ROfuB>5Fgr<91dPHiEASNKB@l-!o*-R0M~uznfhK@Gs| z4G94>t%QSAj!z=ysj8{6K>;p+M1s*glLXCsKju$j$fYYUMA$ml(O?z3{#<@!iBR>h2xI z&ipMDWHTqA9|Fy0zWkV0kp0r$(xZfBN+tn@5*Ml@!vsx5(aPU^PyO5r&l zktObvb18u3pf%i0h1-npL!k*P&~tk#w_Jn~2dor$q832p#obtz$VJ(eK%~xW={z1` z8oK!|g`gl>>{!7JqRbT$c!<^O1l<0PZ;%omg(HqBRWrDp33k20z*dzFL7d|751^O( zYV{3x^QMT-#P@>YwmL})HF9aF3%bkEBDX0j(2|j9foHfFAiH* zgrt)@-;y#Q+LW#p^xRK6n(oKXXEEYGsbA+*EliwN@^CG=f0_gk1!o^i6AtZ>K{k`( zK4FTs%t%^oSpQ?j@FYNJa?*dRI)otxSIi-dC^joWStiPb_rMOL`Qu9nFK?(`=M}H- zL*q*I%t^tlO}Dx+=&ONV@OJK}y*%I31!K

k4?UBUO4Na<2*d)gRB%&?k!1<{(#xvP+TyXQ3+F+G?afm z0pp@$M~{hAN8zKs(T#mZHHFGiLt!9)t0Fs7su`2`x;z+JN;Z{!G*GIWliNvra4yx~3pW ziDe!sz|uyc7t@72o5FLfJ>&ZqetKv^77?Zc{~CnDHv(9Yxfa4N9p$3x#0Y2BQsJg` zA2pkV%KZ|4u4}8{E>t)TBHvWyEc?LWeI8wHIb|rjAiZ(%u2Qq6w$WV^dk$(8pIpEk z#YsisT9e{pu>RH4%f684gz8JQo4iVPdiJM#%gnkLw|Fy3qf%h`0PhKN;O>K?Jj$!- zcbPN{vCDtRWgDQPDaDkm`-TA70|gO+fvIK1I?-Mv#K|9lXZc$=h-ur}kBA3RY3*>$OUQh)1oadBkAI0P(SZRPS9D%Cc=d)Le;8D@`+__tARnf zmGhshDoGJdweZ=TsS~{pTYWjAl5t=j^B(IyRzi}Fe8KI&4rKqrt=`gSH*{%{^qH@C zW+1bvSxh*MtVvNk^&656*oND`5f~H{0sD*qm%sc{4$M^htU@tuYBG#yxALsyNPTRs zxQ^zn^n#|`@@R`bnY4iC4W|3)I!ZX^(B9t92}eJi*Y3vxwxK`NQ!P^psHIi#QCs}( z+%LUF5FMGVn<*Zlq8o|;E#AlMab)v27TfT&IF*F0#npF1Lzyvj8e!Et!S2!@oy}p% zn9bhvcig-YNO||~`dxWt8hb9}* zC0Rh|oK=WsD-LC)T*=`ZA0QY)L(fuDrfwPLD=yEa#5&lNJ+(0Vk^BkG7&NVbTSy^Y zL-ScRT|E*$cknSh{!sAl^dGy+0O9jkdH63vge7F3YG_G?R=S%J>bKJ(ZMhPt$p|dT zGBtV>ViMnN^xBSHGA6Cd@?a?aUhMy9sa~#eyxu{%@n^mX5qOEkhpm92+0@^Ie$Zm! zB-%JLDHT-O-f!QC{+5;*8RV=S9NT+Yj_gE5=k{?^`Vd>j8vD@+-P1akOzsvaF0>$q zjWGuBb+|B@u+LZVV)ca;`(8aUb{e--KnOS$i}Rx<`9?db6P%OnqF?Oe2R3o(q{clv zUo4~so5Sq%j!+nxY9YB0OR#iJICO%m2Ovz_M61;y-yZ>xDucF}L{OziiMN%R7Li9f z7l{#}u-M|t5Dm!ywB?t6Ai69@+S;CFsz2g>Wn!?e+JLHt>oO6Z;r9f+3L11E+}U6z zgoj~j0q4gk&TgmsT8r?=V1pR4bGFYgR0J1c-Jm>Ki62<%Wi;2*_O<+e+xcWhNJwae zXrG@EOB@f&P79VxQ{op2)7Mmx>;}efcT&OC#XmIj+&5Ho?-WH@J+M~0Q9Cdoa|?0> zDu4K)=J_)}Jg*@v*@6z9ak!)Kp~OXpRZ$HW9p!zSL5N8NkK**HaO5H<-s-0%@K2R8dSobK#b=vLXKJyW*juZS4@`scl)jE zuTrsvr^eK&q2CFqhRg}LP~;ko$|j*MvJ%-uubUl!$I!F9RO8FanHYM$+?-XjB3?R; zXGPm$vPd+cBuX^48lz*di{eeQoUpw8RQk@!S77S2r-wLHFeEW za_K>Jt<<(?aOi%$&cs_gJMIjkv=P+qZcg)TZS+xV^d&cOz~V)FG{Vz$7g?J6^x=+V zpI|D#SQU2&Ux$D7U|Bj@rO*8AQF7Pi_UjGJDly^Z+p5=%s2u!5BMM9243Rn< zi4B)kzmrzZK5%x-c2eqOv)SoPAWmQf9kp_NSvcxC6_~tutG4j6uJK-fll=O*Jr8@o z+nQQZaZMn1ilgo7tlB6Zt0*BL4EStbvrWMF1~YR4CjKRf9xOWwol5hGN>N1wrO(x| zI1sh@>G2MKh^u~Hz-0&1rhy^?lck)63>Tv$1!+t?b(>xl^1Vfv7K!smoV?<^awZuX zqvjDy#6TvtK}wla@#76UvFpgM78}$;VL?@ph8P)vJ{W4tjLGeDTHu~0Sidcmw?_1n zN_XMMOQvF6D|J!V*?2-@GUPZqzzjSu(5~<{n@1d&iG-(41+9FgphaO3>?>`}Peg~7 zzamou-A3ipd;Tow`yYfoDQ#?Q%n=zlrPR8BgG_*4QdVqA6p7v|0IehWp31R$eaXU+ zbF-v`b5|ntr`O|Ya@ybZOI6Jwp9a(NI;2nl632orSI4f4qF@Y;*dr;3XTfVclmExK z=9vwG`@+iS{=7p(ar3^{)RY5r)-U25Iq<0Cr3Ipig1Jp^;+t@kUf?$P@iBJPcHm6u zPNo~7=*l-mKalDNRO&T;S($_`NvRN-*xTdvZ35-NQYwhHtovqnAj)E^n{ECxuUw3& zi>PhtXJHYAHz~gnN1Zy)9Ayaz@jM;yn^45Xl3dCP$C;U}TOXx}rBu__1$e(>8KHfI@yTQGO z{km2j^qg#pEJ`+1YIjJXh)m$U-Hr3zr1@WiPxR1sau_ge{^+;SmETjP1m?B=>#s^B zM6o4W`~1E&;vM^m5z3EEh|)5uU^a;ku3kfp@FcJ|saVmTjvB z*bq&+r>l)eN`!2Jllm%d+cd(CY6wv;J5vQmAoM#b8brG{CNva{m7P6r<4jUM5LS*w zBc;N=f)HHNTMo1@{JKCv?VEUO=D-#uC?(lf5Od|Gz@8)Gq(K>$$EwqdQUvybeZtrc%3ogcexpH@b^47M1TBsjJw zfhz(_BOaP!^+2CA{e=7#%WNN)&IwKq&4S76WS7M+Z7278X8f92hkgwMaRFR9mX(dF zDRqHY))TU7YNm6`$9I7!_WHh?sAO1WMbGz$0$_?khL7!s8!vHZcQ+m`;9cv-whm(z z7gSSpSoY8r{MZ6QW=Q5W`UuMNmvWuf8~OjF^dh5SP+ArZ81LMcIaa1Bfp$%vP zfocim`iD^km~u%VT*>kAapR}Q2kj$w=b;>r-V5Q1iV7lgCPlR(d6R-QByNcXE1s`5 z4ezQJoLB6dh~bT~a?=s7m^q=bu6yUY8MT?)nIk9G$VD|O+T*%u$`Yrd-1MJSUY5Q4 zt`Mk#ON%g60l89=4#LIeIJB)d=e8=+iHDZQ#VMfx{rVr`jNkww%Z6&G&+-3`>Vyf5(QsYrornLVf>8!${>e?_oAT3BscMd4s z(%{gIba!`mcQ;5#3?bd!jdV&kh)7FG{hRN(7pXJI@+Q8Gx`T*C7tpWK9jm;q|y04u`+LsiG6H1Np3E!*teUF=FG4U|gEg89}n2)6&z4x8*& z!_>+{$&sedZfk+xy;o;feo|wvC@dk;WA+aR2%M~x6q^{kSZ&WV5)nLW{`g(;99$51 zo#Q(sk}W=8R!Ma6$;^)nl`}))UQzYZ8CoXV%-!RF-|I?4OQ)ql+yYd*Ey?5%lp@tL zTg}TL-FdAo&UK>29JJDh(mnKYt$Yhsu(@;?gDCPtVY4Z*+x#lp2x11cdYYj$8RTfC))+B^0A28o97tON^Yga4&-`yrpj$x!#P5J9 zWH_-?UbSQ3w4`Qa#ye_W2aPm{4=9g4!tV2pN~N9}jCU~&0V=~Z&a;sbD`@a^NHTe*AFHe3Fm9~g zmQ+gUo54PW?-z|9TU1jita3^gq$#spRlqG=U^&j9-wG6?U|Q1_>14>~aB!mN^+gYF zXeqdhdkEA2InLQ`T<+a?JXR?V!Iep+XqDmv0`}k2-;u?4yXgtxM;WQn87MmDQ;Xt9ttz?T!ya2vJI zn%CWkic&nbdJ%z#Ufb4&GAX%!gj0C=fwKpL0;`yFJ;mr}h=|hxm64d=Y)HO}@Ll28 z?$Ky2c-qV-o>5hL_MZ13$M;1Up`3h#aiFl7f8~Wj5z}NL5e0CSYVd)8GE_t$PXznW zw6F9Abqry-*h)NxgDBOSWgZ_DJ|b#Q!eK)nUtxz=@TczYK!j#!}w z)JN~TbvL?qI-yhD-h{wBn$pm>N-9CMLmN@kLFl_1*#A5K>Yla-)Fk(oS^gWInu`_k ztP1vP`F`gE&sVV~~K~_kDkmsr z-|}bhGsqDqU#+rW!76{*#t1mdwEX*Bo=AqYLQ9Ds$YZq_WE_S|y*lJw}ewc=i2Bd_bKXu5ba=GE`EtrC2Y&af2bQY#B zf2gwg*6~gQmI7HBBTa2rTj4`aC-X>RLNfMgeX@pFJpn^`+RuE`|f`CNrSjRIla27gPS3cYEXu z?&j@w+o>nr=Ur}rC0A~0;eA$WPn#Z|MA!iNlHiBac69$MZvWt9I)ws4RSGB&(rLL_ zvA!tg?m`Bt&?DDWa!$A>RqbcM|Hp#!tD>}sbmZ&oSP;zw%Whn`)NjB73Ya4tRZwcL z(_hlrszM~N_GK!gErybS`Xni0#yRelhLU*~2njAQ4j#nKVG>fjePi6iM^FoBU{z62 z5y0=$+jv@QP!No*3PR<}VU8qO%7X$DL4D$ddK0sa^_K*A7qEp6Qfh=ssHl_-5vj}E zXfU=Y0n1%kRUZR+C|p)xamgG=cH`Of*ttxUGL0iu3>;l?o=blk8BzjyI)43YCwv)vJ)W(AXu&-v!xtw!Ie=;)LspiN?fs~5s zE=wZ=$K#?4G)g4oL-IU1s>3h8Tn8O%x4-<_)V-z?db)Wl)akp}diwi^_1WXP{^m^{ zFkHTFM_t;$)UE}jK81m)z2WSE8Qj^N$F1C;GKCum}UshqkQjX&I<0U_eVt#;)kC}P^KS;<~)#tt@)rKp5|THOq=ilY@6At|An zX7TydrmjYQ&RyTuS38dx0xPW0eBI7c@B-9HK4 z621J6(ynT)xRC$VCAmXdPTlLeIMjAn;#;(QALN0PyP=f#gAF;Ub0~uF& zBt>1OE#;XFqZ4S{4PUrCKe0Hhh9`~%g&?y!l?%tA5)p|aa6Fl&j`Q?395|iC?S5OZ z>b>Fz!Q#$Zs0OmkW(MX)c?9-wqi7{L<&%dhK{(h|Jet$j+<#@Pq-ZEbuD9N`k+}bAkzPiBcs3TB@{N@_kFBlnA=ch;|aG zKezkmI0iA z%;dqcHRo&`oI&=_tonPi9uwR7p*%YCuPJ6@kO&qysezT?vr4??49*B~Fl~<{cTj*9 z4H0TK!C5 zu~l!J5_gFbYa6_8buZ2fp6s zWXw<`VZ#PN60ld%WbLqlZB*Iq?i4R6b4_9(F+Pp!OLh07J}96E8L*|_x>{LUBHyk# zqgQqPvjY4?!|L#TC=K?_FCL6s^-}Zwh`@_oI!bD(B+vX(adF5ld+D9|JnE9`d8{{n z6?F^KVV7+UEjy7MNc1qwXi^lb?9QvrxZ`s+T7?|Ww^S}Di%BiW@HBMhc%D*ah^=R41$vgE<+|P6SJ8wc|;s1oJK_xUBD}agFHql z!$a}A4soRO0MZ1K#_?N8*gnIUUV{i8DaGF)&aa@Ik+S&izb zEm#Ras|wqSI)v4R4%ytg?*rTnkQ%y=b+buTcgZ^KQiZX!d4xRW2hA3u6Zac>{rwdw zkr&lz{nnM1@6@>g;T z0`MW2+p5}`RqRQz3$G#5T6k0(m#n0%S*mSEj4^D8z=V@T4a1H{S~Q#mPyqlnp^t?> z^jpqoxN6vOn?>_#Vd_VL4&}0~KtxjEN@bD4=^k5Z2 zYGg|k8%t}JH%bg!JZ2b9_ykEs%EqW?;Xv;S=jj=vpI&tEmSx7W|9b6D+rF&S4@fY} zv{lvxW3b{IDKk)dz%f<`3j<*fIcY5RsMaHWl&X)9;4-lN95!u*R-m=ArNahl?uBGT zMyR!os-sUGVaMP6>wYZQ`e)X^{MDUY(8D6)$(zAKm4rAm+VMpU)7?9Zl#lIB(mo>B zSG(~w>Nbk9{qX!1$hx%yP2wFN6Wp9~t(4@bx^%M`3mnb@z3Oll)VJ_7QIv2ZiVc%O z#r9ZnZOTVoKh1{4VtW`OiN~vOG8@~OPzw-sE{fV z%zvj5gvpTe09Xfxuj{l$yxfKsd}lEwZ}B1jy84G_y}6tPxQ-{^l7n)xY8;`eT+{A< zDFuCeJa+F}Zf;M$cQCc9Wx^#Y_XLNF4j==$16TsPN_0}vXZ?poD}XUKn2eQs*!lgn z+~}BXo@)0eURzdbqqwS(2`4^wWYB;`80RxE`XA3jAMLxaQIgIc2K^2ypG%0m+7s)N z&#oY(&^7ZfTzQAkL8Xqs5u_x+UAL<%E2Jd#jI3T`>EszfX>&c{TBZvcmG2BUc+0wq zjHuz5VVy8K5<%h%E|Rqu@ZgD1D=4S&bV&?qzJv53VahVPZcT&Xn8iF~pDv}Tu)c!I zEEIs*=q)%vkGzO73s6N^p=~}tD?Fby-b_I9tAwrR8qXh1Mp*G>vQ*t}*^KY({NZn1e|W^er6BO9LxR0jg!!Pv1vV1z(+ip15%F_R zTs^k!YOCj5s#u`BS4GMwMJS5WV$vc?75|10c9;cMto^3cW-@b7^uFPe=Op_3RaVzF zj3*HEYU|0_weNP_sXe^2{_m+CQ@UrHF9CujP;SQ+Maqr`4PQwmfK=F$mF+U_vZp)VX z7y*eFG5ZG-#Z})C{o&ZWptP37-B>kxuD=xN~1-3uDjF3-h!18sD#B%Je$(ozOzw$1LKkrM(S{qIjLjxAu(cz;CV=EpN4^3gZ@A{eM*O8lZVhe+Bc?e5pwdB0)MeAk>7KvlRX3P`#9 zu2p$s2gDKRLonjQm;bqNUpzucKV!D7GXY`OSq|MLsG4#|RHnJ9Q9^otm&&@0CvwHo zagM0Ln2AO9dA9uL70LT$NnHl}tHgtm*ymh~VJWvcV$7l$IMhV6zy$+_eVEjEZtv__ zWUo$&e@_(rQ-ky3i0dPO=D}uM>uHl^X8eh*TM>sfDTJKeHG=o{O)6V7%O!#oEaAeM ztlcv=!1hUviI_gg^o8oAg3a>wKTEI`Dmke%aZ#7)aUWO=V@hI$lB}+_T+V8`Xua!U zo%KMf5yfEH`0I=I!JUBYQ6uPNRrae;>Z8%PZ~>j+&mLvdXN+c@D{?&tAnpPug!8DlpZlQ8BhWiZP-Ab+WR8)SP9HIDX`q z4<=^qj$@u~=qYUax8ZP8&X*ISX2|O!2sN-&N#ZO;CUu5pqf)%m@Oc)WEVywrszqo7 z0#wA7aHg&J?qu8doyf%W-2l-p<4r74FcZ!Q}=R;e3B*O&-}g z;zao4<)EeR=j)8j%-+XG{B!KuFmz` z+)o?}nL;BrnvCD@klEMuK-5J9nUvx~W{_v_M9+=XSW>HmP&9UZr7D4#2figLLa{1c z-HE88S{D00uT=3@)XZCYCE@Z+w9$!;OI>v%PtO2EGQAM_U6m0kcH@GRE#4)sEsFHT zm}pJwFX=NCFma5D)SfkkN3&OKlp-d|bui@81XAC7Z05^1KrS|#^=F^(<>y?Q(LMP&mVB5C0B`LY`EY3EVSS5zJoo>Z2Z1PHs}cuSW+Vu$@i8R z9qxW^o&EV#{YuVNP*t7>e)ZjKtgIJ}z-wSf`P-z(Lag4kdG&MQOi%pFUHtCU%j49= zarg6a%j4w_Rw1GI`}=z|mHa7O%Pb>5KR;auqd1oEBI}^-Wfp%o1H3Z zu0ZF@qIbqywG=en*qVmx6bciOni#T?Jxs^4@f2(V3VKEo7^$pd z9;2A-$l2$tVL4aO@MkWf4>AdAg@LWv1oiE2f^amw9})0)-U_qh>6$Ti;&A$dB$U&5 zO=9M9=^Ts%hh|z^BG520eQi%of|&h$0qvBazkJ`C>vxn4N8y|aXw2onbWhe?t*R$I zbIg3ckcV}2P1%fBQrg&%AVE1{F-u^|8v=Ovd7#HRUFTJ^wL?iMwipiU35?}&o>WgH zC|p|l&J=Tn)9sAjCV*J;6T-yWNrjMJB#6WTfP#w#wy9n|0JSg;@FVlCA^jqA1T;aJ)8*nEfuI@9Kpf*gJkNRQJ)O>%_<~b-@iE#sLY_ zpl|y*hUTgUq!K|X>9Eebf2nB9@+@)2TFlETKp#JT+~%F~eCKyy?uX#)?0omPL@+jT zG;+tRGts_Gb}VH!q7Ywi3l|Sz<`|TP{PiwKC#_sVAQeV2;exc8)f6QW2NA9u7;U2XE3;JKAa2hn-(ABZ zQqb1J%E=8`RYk?)&#8m7Lc(!21(*_Qm{UK8lQXgtSAk_wTem)MWKaUj zk8%PeY<7fDBve{0t=KM?!#77cH?}|j%Lm73?0Igy^7z^XrrK$5x3@m5UIvr*G0m6Y|Izs)Jv1W z5u-(k`$VWyp3-N4QLswZg9)pGZF?7}P5+7icO>(pq$P^WikXY#q)7^!rjU{mRx=DF z8wmrhXu6n0@T)I`y3UbIr&O9@q4Z1HIUEI*jwZJDj1)J%1vT;(0zG9mBt2||cAXKm zA7j0dLPuQ`;iGDK9CBg`Y_MTgVq*ob!dqg#_uB)?F|F8Og!~IyOSBJ_Alz>1Mr3Sp zVHT6an|6Y(l4-k$4-~}b0&`zVmW%94z*N$%YG&*qb{GKm5xEK!f^l!82((?4Dz7i> znjeUcBW6C>x(c*OOMcstwBXWp86PSl8)BvXbo~oDwc2&|^_JL6b?L7u-oGgu&h_Zz z5IJ*w$S;K8YgVlA_^_rTv)ADk`%TqxSA$;lOB(>{nh-`fG~=o35q1fZO@yi>iAkmoklb4F zpRkdi!-s+Uon`T9t&J5AV-$bpa zgd9e+O0~BN{{QAKZkoGE&V0|jFYx>?@a_`H?lD=Mx8?YfhY>(}w?j*Yx4G*W7__D< zjx%;mOY3(6Q~g5gF4%D-0w`0CHQu*&9p~`OK=g&aZLWZx&sOFUdj~shH=8ZkmTJeD zHnp^Z#kL{GtpwPy|3!Oj>UW~ozPng#?#9LKR;E_RCYbu+v7scGTS%UcDy|f@kjkV6 zG`3awZ8CGj8?^*tMd?^h@stVAeW?;^5x&X2Pi%F}DwknpiNQB5bS7<^(D6IQg)gjL zl1)r-ZeME?X*_sY;6xK46y?!OfKnhU;TStY!&6f^dE$Ehs1jXU!AoNoYZC@4L?{;? zw8XKn?>OldNDN)B?NUe7aDm=0g4DADTlS~vV9ARD4nO@0hu!Q_*uE2uYE32#WbR!- ztzFPEfB8yv@PWm->}x7REmKw>an~ZC3HfgU`o`6!?dDFWI7*P^jd4gMftPph2DsyK z@WJ7J(DrgYBlY+8;8f;gj{g0{C>d|Mb?cn4soR)0CSw>C8Y`@9pNAQX`C`mq>aVL? z5>@n{?q;vLEh)3IizZ-d97je*e)Zjad1eETX-=9+i9Me?&eke1ww^t_7P%RZm9eG^cO$vbXf$*V_X$7P!R&T98zc4)EH%`ArguUPK*Skx+F8-Gsr#l#ly|v^SOw(vmRY&#$#=#uo3~13s)`JbRc{@}mwuYCN4oZ#D3}+M z(lJb!5pl13U<+PcC>R)-!P@(-YS(tu=!6(MEpB#BdZ#Sp@^J6=WTftL49=Sn#d?t_ zXA3e~t*@~yYIdPholhXe_!K~roVfVT=zgLtqC7M${O{4vH3>vg@aKjeC^e^_xvgSIJJ z=DB3CAP-sVHSPO9{?-0ez46D@XVmX(#cBaapGp=;A#wM{uOvuPQWEoVd35`_`&sp; zEqut$sL+iN01Od4K!=aVRB9BDLIUMTN%3l@(xCRcnl@f^8y^@Agk!)0h=z=;tiCVm zx}oY_m#IKaxI2>B|NckIewsE5H@Etu@AFUnhkN~gA%U~J^C9kTOo?|Sz3FyOl!CWY z+yEZQYTbFU{0slz^ZvV?^zImGXi&A!b$P@tzOr#iV*nBeMlTOj! zdO&Wnn8bA68?uU0sY*^jb)*8bq=$S=QgiGVx))IA_w>$j!|po6d8kUAq|AmRDSqicac+x4O}Tr*Tr{Qi z2>MjCMN@qZAQ$fca{mHpUmxOJ(hFYdKE1v>mk^9O%CrOqrYp%x27XDN#*PwBsyJ+q zE~LAyRZW_uCC=hw1Rz5(j?esSHqwV zCe17@+K#2xma3`L%0Nd z73AWmQMTjiq=^F~Q%>l2^iG7*U%(Nw&>)2eN9e2p0y(2scF={9kmgaQlETqIs;GjI z@%^UD8KPnx%M*o>mZDR6oiqLj0@-9bRymV=x0M4h~X^18f^3H7)tNF@~8; z*@f{KEocxAs^j2(`tBHGwfJ|O9gaacAeQvKkq{W_`!Rr>1KEC>6cqt_B|<(1(ToY@ zh)Z6sr%(`~5q5`0qj#LW@fcRmSOc{PBdG_{)(FY5G)m zl~}8VJ1-X?NWEh-U2z1O0~JW_j?4%~Py!SISyw^_{w0?%=y$~uC${27%hdF^Fl8MR z8P6(Ef6R4)NzAM#M8%J^PjUAbKb3>TUR+cKNK1iMiu?;o{YTMG2*9alqiO;lvJ%BB zCs}-`lH^(DN~Q)sn;zyxM$B?NIdlottDOEo8bVAhMm+)rDmah;HNTd#ZHjk)%6qP2 zL@ZboTOI-_Ncgk1ob@#yel6>@v`BxOP z$DdaWR}-+hKjL zm-OSAeUD_8f4(am^T@po5y%%sy6cMHcE|wRXM1XM(F*YfE(2tH`dcIr;R!+m_-@{IATOV2ycoB?CWu0h$7XiUOY2}~6g%yV+ zI+1Km2FFN;I!@5Q=1KrW{Z!!Y17-N}k4QZ7tt!m7I!czfvYOy8!i8q4v`~U~1V-3{ zgq|fhAeRRUP;6$|yR{f3`c%TaFYo!mY)(TfCWLYg__=R*;sT`QN;2^$d_yPsPEr^a zDv&i!VEXB;cZV%TtT);Qq0^{~DE&x3+tH9Z5-$(Gjo^6|ahJb3)r2G`L;eqD3+@pPX3 z9NlZG@3gx;tJ>I-q_piTlr*8{l;?TN3<@*!`jg*(aY%ZFP5}D3K?E%6-D$|7XElIN zeFbxROGgD|B5E;|HGHxq=JkPd_j{0UscM(!WWZOGYUI@pG1N$@a7y9?^dEG;^WYXB zmjmpp+dPwD+^4Y+RmyH-COWT47ji7++Vj|cQ+*NJ-1Jk zFTW!H2#rli@RDEJgbmsKtw%F24FvKQ7qQiTZ?JQaJ8ppDyS4s{*5i!-Lt#Pi1WUCF zt{8Lye8?`X!tNzD=DI9mS{ov>U#OPqu(}@OMKk!>J16LFV#1m@_f4N<5A(tLL5}mX zqE@1}dmVw}O2Y--J31z?#>!n_2;4t0GVEj^!xb=zx@_iuDNEZqDN+T{@KHC}O?lya zuHcG_C`T|2sG%+A9c@i(`%XGvxLnjyWcT_qyz4sSa9G&EMlxPXf7uH}-> zn;f9ij%bMgo_zt(rZM1v?Rx!6Aa}o+zZ?uqUF%k+J1VCdpXR2Q=Q0nDulWRB=SrqC z|7?9`_Q2fu*VMdo`|{(=*vt(vc^XBj+a!E$gH~4} zMUL2+PI@J&on7@9BjTBtMruj0Zu}kR10BuGmQvy1P6ti?b$NnFfGxD`2-(_>pRt$*LHQ*?ReC~5`%EyHj_axnNy@$ znQ+*od|rOiR`<|hRGqd>`^R&lo2SS6F7w}b6XG zHl_0M>tC}#`@uc?s8#mG`tITONdWMWsyYv}I(A9Udh(u+@{E8TIKoA>RI*~ibMy@r zG6%!8(rII)QkloG*4-76Dib6SnH)w6)Jmw|y1qw_3>$<}{dGI7{6nj_Y69NGH=D_f zln`ka!q1fO2@LE5?=>So#s!L4v~{9zss9lQ<}{_);8!lgDO~4(qyK`sSgi8#~C*SM$_d^63%_ zN(ta4iCi~sm^a$4#DW35%F`8I0pbUdI$#OGC=>%UKvXC_nB0RA(~~H%AUh!@xgd5! z_yBI9j*)vRXaftn1k_8x$SWmOV)5ojmD%5N%vbgj;dT!jI&ycrzF)Fh zR7Q8xQMTkplcSycKmUIDwrsU?H08kuI4I}wWKR;Za`LzvY!u=mVe*=VF)Ws5;*PMJ z+M9d&9(GaprYWIxp-haMyxX3| z?@n;JW7=$`h>f(lcQY(`C<|d(Fc1PL+LB}=u|ziZa}*Gnl&Zmi1st^8!#a%1AbJG1 zNh`OaVh&DAJ5~+2=Er8~x;o{@ABPF4_Cxn_u7!%jm%!3eL{Wlza@;o}Uj+q`PCaI6^w{ z`H#(*jy!Wq;sBL44pJCcUfqWB$^E3S>*>J}KoI9|p5f``cGy0h#Ek@ zKIP!UD`O#BOc+4fr6KT%GPu)rFoASie6V9C#N<&+bXMqMu@C5U2~Hd~?^!O;V=3LK5wmK%1zn&@rO3;06IQk@2tT6A@pyo8-Z!bl$*EFe{v<1^#KR{HFUR}duYglpDmhj zc_Ns!!a@8lKc#P`P~sxp|33Y0vAHW$t5U5LKb`~ckL=!|jkKouT-zz%yR`Il$6JA0 z@+eAGMqC}YWz*M$UlMg7MuA1BANB6tE^@L0PPS97v#80+W^7aqP{M5P-aWa?bbmqx zUd_eCK{gRWy247gx9DpRAiKwrSp0!EJ}=hYWS^Q(#j}bWit6nqhWo)+jX&&vDkV`y z?yA623{T+~>X=PHqt_(9cwu0|&Cq9N!S&JiUe2Nr22x0PO38xB)rwtGsm)gV6HwUF z;xRwOtbe17pz{|L8Pf6HpKM1TtNXT7!s5PFhW7v5{#(7_@{v35v<5 zy5b*dHQ6iKDc^)C1FiSQ!r@)!+>^#u-{=P?N=Yt}9e_5#cbAYV;~l)Wfrw6{FQ8u? zUZPLR?_Y4D$L7v9ux%{HAi;uU_&o8Ey5;b>bmPR?>Wl#}jQLxY(1Nyf0UG8aU{C^< zP;w$AQ*uEEBO}>gPcH8BZ3iSX2vj-nxXnyW6OuI4`61wf%rm!{sl_py--V9^u+Mz% z`pJeipHDW8yuAM57&+1gxfHh=ny)tANWw)&0KKb=)+v9|+YM)QxJ;%>bN*cdK%|tM zYe4EF)(@ZXiY2wC+((2V9v(fgE&E_ES*e2QglluSk<+prMs$9_-AND~9bFP4nkJE) z5?>2cW6Jd(83gYm6(~y)Ja*B$FtM;OiuV|b=r7}jz6?I{fl~&>&4n0i|6$3DeQFkl z-aHm$n>`27tGEGWQWMlT&bxAITIck1Y*PJ{ z9gAis?WE?6g_Nh@Vv8cwuvCtGe`FZVjQt>3W`IE&9{|lp`uGvzhF4r=+S6zgv2S?` zmzY9Q#Uq0zMQL_zzQ>K3O?_mFJ-q-ROTeG5W3w=4U5qzjJ>n##>I6zAY*`I#Q;g7y zsQrh};z<27&oVGBOFOHl0;Q+CU#*oB*5{cD+2CSI|g1* zTMoi*=8&K4kf_pZhYkW|jw->J61BsP?AR@ycL4Hl{`eYAMm|*MsEd(S0QolPxBudpFP>x$Wk~UmSug}_tE`psajr83l z>d{Ao?~2Hm`x8rDn`gUWOKSl~WtJb9n0H#IyqR)e9uKRjBu#O_LPDmO+CV99PG~J; z%JyTTVyeM>>EPD!eB zWgGlFK^ra!o@^zIn+P{2dGt8)^K`AJ$a^m_CQfWp|7XXii7+@LP)uU7OZHZ>#io0$ z(RIi_bCH%ySh}wk8}mS(n#Y4<$h>Q<-xvKe2l01obW)U;>dsC8HhV!094)zB{tv0{ zb|OBki(R>NHo}Gz5pm#(R%x$;pv)Zc{g~w#9RJJlPRC`2Pa#1W1sDNtH~od4FUVdn zfsvM;pLNr+&w*=-A|&9j4M=(DKhLJ0#{v#n-qX0b!zy=IAWs}-n4wzNmQjXXCWgQU zl(Ui(As7ZwjdpnY{yA2a6l|0hwyzC(``rt?O2Ow(01Y2dD}+T7#(pbxJzWy=#RXeI zqi$cWA1-27y91+{+L7%2A66az{A6v({lt)8yOF>VkHlbJws+wb8pXz@N-PD5se8vI z7Y7UHvPc3A?P9sv-_Le+Kq+9%iNRDH6Jrn#?4s1g9zUgt zg6kh$p#4#SmQEEGQU9qaIdh2pnw|*uYhskB)NeHWx8)sneu_~a^U8P^roU7?h! ziUlhHR5^m#f|LuHviX$xx+V{4++m5h@E4z^rGu`VXGRjRPErueWZQ4h*knFNj~4Uu zjW7CeGXQt#PfeeIjaXjm%=z6?{K@cdGE{l3+W z8?MJ8`$vR6mXNcDV;@6Lcca$9%`1T-siJUlo$rw&t`A#+@}ij?Vdrr-QU(#y^EFF`D|0NIG>LZ zy3Opz@cpB%_uH?^L(sy-Dk>|1GW(2AJ*$5Lea;fU?DVxRvEMn1;B##}RTPyf18&D{ z=NUZc@pttz!@s9z@b?UiKGYq0u%vj1Rbf=g&lH-@qq zb)ScJQ*KZh5nL3$(TzjOE-tr|SnqGnWRk zh-2MeG%zyUxp%Af_wnPwDdb>r8_t)Mg#{gErAP!F)y-vXBkfu<5bgC(V^FEY&3CLM zvs+sp#z!i879IcX(Q`E2indmj>H~KevFKWjPlw07o7A>E=3V-?B-hk&+`#m`nzobw z^J$I|hM^_zbDypIfPRfTF<_SF{=$pGzykmSF93g~>lJ9n=4wF#KpW`I=hFNIRZ}Mt z7=|4kdN(>PxW1O87&_U{@UX6w3cS?zQB4Fg_FwT6^SdBj(J26ZDXT_@r|TuLw!$PO zd1=ThLwq-n>%)G@N`z$232$Tp(vu%q|F*+AU%Ui)4KgyJE)`AR?=~h{I$D%QRM0c9 zo+#|>>>h`oHZ@&pDv$Yz7;9?@;zQlqW4%vX5V`&KAR!C`=uhY9+Y|Oa?7#*eLJW@g zjQn^@jr$PE&oYbOkh-XGI9;50hy*tvo!`FLzcz|Xp9-YLVn-w2>)7Lb$aL=+M6uw6 znHp@nRQo<|HaBn=7e?`oeYZ^`9X%Dhv5rhKI0O{6OOC1{+D^0Wsac})K8%3QvnhGG zgc@GWi&CcVJ)8rCS5Y@FIi(M=0#Q8MJ?$GC=Iu2j+%0&t)mwEpXczp;QHZdpSk>)`|vp zq!wI{=|IcnB~GGr^K|2&v(FW*h>~6GrFt+28_5=8>H4wj

pEdur(zV7f0fTbLJ1;t#pHFZ1zBIJPzs}5oBI2t+{^$(Ahps6Dx5N+!bSEmOxPOBuYOof< z>={1~24UyOUmWPse%_@BA;N?Xd*mp5@^I}~*O5l1fD`nZljCvwOAm+XcDfd6uIo#zQPy#(ez66IqSUL z86vVDc=cqLI!|3gUrK#siFDn?Lx7ALv+t?Q-8`KTd{T%EbL+g14W0=SR;E8Zm?3p3 zYO?8%xnYLM5;`u~)785gJ^P4V=N}r{L!4jU^l0HB--%t63O(w2WW*-d_MR( z6T@LjpR>-f>|%-5_otPOa_CqvcF!u2-YJUyR@jtRT$;6b<@m=GD*0$#P!S7hEZ5fm|iYTvvhR?Q8J-4+!u7`3jmDaZJzQ>hvHI{gN=1k%^Nk}T4fTqx7!`m+NH zoishQtrbL*Cf4r}3sWKGWzniu!>p^->LkgExpYu=sz|i_Y0bkegVLkBATtFkz|U;v z{5s+9zd}R?Ac55E65x1dGpZ6X#U}{weYTA0`p}2LlQN7?lOH)+t*!SFD3Ha)gCIGv zhNMPP-?kM=x*vLbg?_fj12V6Itnz%7D#IDza&`b0;ytrrHZJ;#f84gIk0J$1YL1V0 zj@j9H`iCmua`gKNpr`a$%fXQc9{ndfb?iwB_-S}ucb_Y&Dhy0L31nnsjyt|+9aHXI zs-n*giKCXlk>zGigDYpwZh;o$TXvo+izhf_)NnB%dU)J*%lBu!dkK|t!Y;;$M5I9F zhCT0O;mGB@Ou-k0d(#JKh#iDIBzaHE6R1$q{J!S1dz_91s-i-{lQxKFcZu!>r$2SJ z!?o3me=K}Ug2|L-WJOK3X$V)+4eLj`diz5|@2Ft;yvEfHt5FM{9A=_TQ6IP)J0p=z zu^itiiMf3d0#4NQWs)Q4H|)aTix$KP)unqGo`#YaUyFZ`BB(UmNU=Np$G};?2iyrb z7{uY_Yk=`}-hMF#*nuyt$bjDxfh5@FyNvaCMsAX32Q~!~aYfY-z&9nGRW-GSz!S`% zeqbuWNLotnh#_ZvgN@eXoZ{KRwQffka6Cdu1r|~;ObYcfJM^{%5$l0?XDdWI^o{zCP@UaFR?g{z>9Pu%xJ;D9n}9h z<$i}Ao&|Le<9GmQt+eQ%XOoOIE4yH+W0AyXD&!)p;Ftc$Uk`M)URO!O1_ZQrOPbWxC{t7 zeeMygC1AHfeVjWtFxP#cLX@vp^KkK{n(w#ghS$355)=&9QIe1Vd7t+f5N94i!KGNl zwm54kcQS}``q=JWxW+3S0s_Kn$G%N4kZlt7A1|xgq;rKV9B*yNKXVS|@CfkFO&ot} zx~5OHB_v~7{Blu<&WP&q2JDXqe^2`oHEyzMb{!RPy^SI>1-P@DFq;z#VFzOk5ltIfJp9f*t%atR73z&HxO8U~| ziO3s8>O(*gmiZ0l(wp>u54L0pE1;o7L_~KVdt7-*Ufbda^#65CdC7{;{v8(BV)!Cy z{{_#ExjZM&vD^2r?A<}W*XuF_e8o)530-j?ezUo3mAoNUzX>R+{CyOE)cb+@T0XB%B80oEkNLezCi4j`c*2uMVIyWCNulxy;KIbr1@7= z+7W4EbEUbiWF>Z`A%%af9xRvHbg6kI~H$T)Y0jL)x1sPdjJK(taWm{0dT2~_#Nq%JR*5~l!mF`jm z7H^)~-u^x@5s~8DR-)nM7Vjf?>6?{XNFx#qI@i2-cysJWVNTQ#bf`#7wBQu-rIF3A${j~{Qg)wx&@g|ODHPxB878Zg-JKmYY&;5MFw@(SmSdkx zWw0qQfv4__2-?Jh>Lp8eeR(?K)<5K1>l?MZ(_15^bwGky=RkjcezNrI`eeg0W_0~{ z61-s#<8SovKt9@Ym;V|xB^LO6X!^~F9aj$f*gM~dJ^SHZZ0%Xyf+7!a{S@kCEFDvT+^dV0J(5@`=7+K2U zEOJ7et6BP&6BLIzP1qN>o6d&hl2mH(n-=jwg^-;x)fb8Makg=4wldtb;U=RDwl#Wi z3vW3;uK}5e&93k+k9EXM>{ofB2m0lH#ojont(%94erzvTRuOGKpidRgV<5e1!i7Ee0X*^GMJ!MpB71=;-#PI=C1 z;Od`rc5FYl#+#S?nURfuYJOVs#vnsdRh4^dnuA)b#l*^DFNmiI-MiL?ixjQaw>O8$ zqcE^FZe-EVu{Sf>^fTCg#kadC%8aE+WtL0>?V+Hcyl&2dM;;gJAnTczR#K>*c=jb; zKDg55G&VNjr%$UI&aKyfZfoxaSfY*#k9DOcI9OF*O<%qC8eOmQD1M}v{^Gu+1=K#* ztjwTyx{Wp3p-?+n+hnrtV4u_7>b*G<7mNW!PozcOTj zrm%}wVPZOJ#7M!anq?>N%)*B+=_WN=1jB*dIc34cYp&g7L*@=PQ8s10?ahuOyO;KK zqsxu9+GS(q+SR|Dh<>r(MqDz4oj7IdcXR!1mLG;M-|4mjEI&n`&iYsV_6rk|lN;T4 zmHDd;hnDUHA={jKH8}FvL&=nk#bfljH9?`Ez9KI}xGT%0231q;WMk;=a0#t1QZlJ) zd+PP!;^mI1xKfE8rzLLo9O!GFThBkF1uY}xG-GR(8Tu{;ZIX;WPC;;(*_v|Xc8uO> zss4Al2=i#_{Gu--LaF{zsbV%;DX^QZ=;$%SFX(9A+voFr`h4W-$2v?W;j0j7)}$QIAi>B>XTE(ghM8R&K|fslI8@K6!sgT?+cAyI?hR z_%=(Ge_T3`B6Va=#euY+o{U>|C_3B%?u!qJXscRr$mGM?m0oA0(cCVao?D7SYVIR< z@egY1*|Ha27z&-31^#>9qP)CUg@NL)K5tlN@UO#4tC{%iCxS&>YWM4d*Mu+Xe|g?4 zJz5u8 zg@$|3TMRuZU!6GbAEb?J=qh;yeBcDkF`VhEKjZjkWCUI;3?Yf7imH>mdIBre*>Q^} zL|;)oMDx7O0>M$pWG9`LvULySiC*!bj><#m(SH-RHZ&+owf_d=yt7hD*2A6V31*F8BrjfEq4 z@o-om=9ARcCWIC#-R^6(HqeM3jD^?)J7%v6H~HgracfZ@gYPqBPo2UAn@49&$81-i z@QZjn?JicyW(SmGM8w2OmyNT&*i@!WoWjC=z(Usk@mTL^qmw8$r|_!+OD1c1XPf(T z(nkY^zO4m96YFhA;?YWHe8~aU#?zjFn!bju>;tIWCNBSV!Y1vp!D|t5B;6evwM-z!=PTw@#|rhS}AH4jeVe#2F8db_qt6f&ZSfXanm{P5j7Dx~@R z(U_d=U(j8p-am~vQztR|jr(m24qA0kdjW)?OZ7T_aVKXSkR1%CFH}U5X#c`NuJl|E zj7R$Ohsy=~F>}&_$mUT>)}k zoBdQ#E%b&&7FjAKsz1tHktiy@<7=A4<-I7_B9#+kZfXS07Z)q%UzhE0|3c1Y%i2g}b zpo!S##7;fE*b4gmAp-(!Ig-U6m;iEq<)pgua_n(TOZ7WhTNlYH@wr2eJ{v;5WGxoOxG4{LuP@AneVwbB?9WKIU zEOA*XNEqhULL^CpIKf{{#t(nY#9f`Y7^lfhW8I~VDutKF&Zpolpuz+`3n~WuP=S6K zTbi5K$YvoXzys^xDln>qVK$6uen(Vl9oML9cI$U#`|{MdQ5w#S9rL6~f^JI?m#-M~ zrVNC*z?Ek(|9x68z5ggLFHb~9wgcOE;m=f#?3HSq+;JBQ+|VHJX>nTaL!tDG z;0W4f!N9=qY`K{D(Hr#t!!0KxQVPV{&riX9^`GLRsiu^H+dPmto@ zAw>HFk@COit0$K1;D-1T-+pk3)W()?B}XsD?H^E9vV1GW0@@K}VHX>`L_vl3P-mr< zBu4ogYadCPJ(FN2w)~iZE{n?(tIRF#AgP0w+gTs+`+Xv18rIP^+4!Jp}vDupx%F%UE=Q5 z^q9qVPYXUb5Yw(bKJ;qS^hXg$p|t>?0Xhyi3~Sm>{@Z&>#~?4i<^Np(r`vme>&Y1J z-iiH}oiOKCQ1dK2U5kQBFYr`Z$qZx}=M)yoF<(O#DgEkSzH2gh*2}8w)?Qnd;Oy;8 zSf%*OO}q^q@n^q|s%3cGT;gZZt^R6M`O|ugz@_6{K5wFexlT?ixv?3@3u{jzrv2{H z0*g;-Ty~muX#VM(pULv+Vp`_?j6<{DFK;%=*SjGtW#EUqk>V#MU;2VTg87$UQ&gMb`;Ba?Qt$#0@1cWhG-W!uZ+&3^ z$vTa{(?Em112esMz1|aHmUT@6VXFXQoWJW0Fss{6Q3Rjt2Pge^aZiQ3T-tlD!0H3o z%-NjAEP~C=mB?onRvtH;ZkP_8I`Ood=B0rVe@LU?tI>yghh1edsI{G443H9k&}>kE zRY%}ebS;uZ7nqr_IMPtvH1G=8###IN=J41~o&nfiB)fybH~k!c+=vl|6z^j z{Z9ISzghL&PE1Hh;N<6@v=zTp*m3uZii#2pxM5|~D6+D$BAVg}Hi)#qW=2H8q~P6@ z9Hf$D7>pK1NE`1veH5pBTpGIDVU!r5O&0H~HU70!Z^;-;^m%Lit z*!mGw&_|zJ%(WvHtI$<3gFj6DN|C7d^T&Gs@r+?n1#V3*ZhzLxS$XY&UdUcRohtJU zh4v1aBsu~?Bx0&ovSpKA4a98w!${P^UPo(Eg4|l3jp}FRu^fvcQI4DfIQ(3vZeTld z*sfEBe{tUd*UNS2cX)#e(~>PAmSj00!c}A?jY4*c;aMx^eB>6wb^n_)HJ{Mu6>)~Z zcYT~~`#NycQS@uE`LRcAH-wA-Xbs#{kC6hRD#x~n9=*c-0DdOCnRr^wwD+?2!#Dh| zsT6Q)bbcfUmdohC2aqbCj&aJJiDgZPQEl#ryzJlq_pg7x-Iz)u7XhjZc-iSiGVLH_ zlQ2AE{P#ndNmg~s@A+h@gX0AM#!#(OTgIbN5Zjf0@6GfyfVSUl7l``d2(XiP0X9>q z(pQNae}^b4==&)`0TSiXPjdu`mu-p3HJ^d2$;AOkBSrv}+`8f?s7^eOQ z2J91M>h?I*#>U1~e^^c64lO0nw_M(ticapo+%>A2>-)Wr$?ibGQ5&9=BXIPeJ z;GrRjKcW=xF54DcZ@(kGuM9cUE|Bn{fYlQkt3jFwGw~X!Mm>KHfH_m&eAA1kvucsB z3T*aX$~)mYjX*k_Kbu9I$h*Dovhc2z>RhM8pp`bQcMcEV*EgmRmm2@g1g@vQ>*CUE zO8;zB=*z{7V|X-t7elF9>jX&eC2#DAiFl2xi3NZ5$Ov*QjmO`zH!XM~h z!03$|GcvadHNaz5MnY$S$bm@0a&(*^yi(umoznxnt=pfo8K>lIYrT$ZDez^g23OzH zcjVZw2{06!TVa|i=M*?gG{4&2jb122F#bCzb@L64K%s&5_V(Jkx2;BR%UuS*%ZaJt zUHcb4Ki=|)h>Vr=N4F>7G?HZg{}x3?253@sSkjRcpPLk*>0Gz+Yfae}@elg%uEI*o zcj&?8Aoj~UT#e7WqxhwqRxU0{mH+J1ohUhUfxjtVHgkK~@H#T?^U#&t#5&h(qYtF8 z{O5phHqJBk-?e1|v(+mrzRxZG^C@`u6KYr}n<3=PvHQmH$@LZ1y{BUOkTx(#?gc?ks{5t%+TN^BYmo}yoSo~}esyHB6*v|{4Y#do)&-x)!7--q13UkN;|_XntF8$p5Sd z4vm>H|FR!fdwRM3(Ub)>^PD}@DcI5U`U!Y1FQDiPGK!B}Zw*TbLdM0~>ts;~0w zd$|wu9}5k?G8*c0q)s#$P6I+Xng%oTq)jaK(-gxGN9Q+~m@AuMB(R3rdwtgrlcrj9 zEpc>>lW#lvDAL#>;D=_cgj{%Oh}i|^_Ajoh=c41n7`WpCVZ z;Hk(VBO`Ay&Y?2b)J~SRkOt_~K}Y;3!VwS(x<8j35pAp^TWj&AY`%Ye4GcUH-K4g++rSJmwR^X8bTThbL}o1 z%jN(V%ItF#F`||7&bc@_CBR%dGl9n(iB1UQ!C-k@dH~ZKJL6wg5jxp#qGf+gay*2x zZHu_X<$ze2Kj%Y~8iun&gM+Ps_wL+n+uIFlw!zI2-!hT5CSKt(KauBM@3d)*kMKGt7ZFK zeWFKLBj+^xUHdDaNL^(M9|BV9b-ya?U!w%Nbng=9QkFDxELI*9J36vfv@<$wPTmBM zsD-6a7^{7e-LNE9L|kTnUP0CNQIlRjp644AE?45tj~E8D)`*)7x2m)e=QQn~!Pf&U zbN+h<(Bl)f#mRcDQ}NJpB~8Z|Y1FX!7RiENOAq5aN6pPDW3c~#$p=?3u;So; zgLJYZ#QE|_&446FL_6Pmv9*H?T5DB^qJSY*=kAW*@^4O2uF}NYeoj>cp8&W?&~C$e zagYGHQ@en0$G%S|L-cc~)@YO;Mbh>eAaRQoIcW_?q4ZCA-|>nd`f|4&cz$VWwRHiY zxtNjCl`buZ0I>)w>~a0s1z@*~44?g+>C_|07jWJJde01H`o(Jf@QgH((~fk;BHyt8 zKJsPeD_1g<K`+~m~o-qNPBVE`v~)7;SA+bf{d|` zUDq|PZh!jZBCvEm{Kts+uLkY9=VqJolP>`}_t0}EApLI3QhhQAKE)*PMh-Zecf$%2 zeaSC{lz^@7vp`PW6o&r*Le4GlRX7MzZ)vok%U&vSpi+ z^}dr!$ysNPO-=TdD7Tp?=Xe?fP7F@&`0GHn;N&=B^0bCLIQeqbteyt5+LBhm%9JdN zffU;-k#?SLSXTwPEOU-Fwd&;eJ2HpT;g~Y8bxG;>GO4)b2F?CB>bc%*tLEHsAvqX| zAxYsvpqiWg${<0Ux~bOUW>28qSHykW&6C~XvWK+HDUjQ2W8LycP82ehAula2;v8d zeaLM0^WVk!&+R_4?RBCDZ1IyuQNvnXZ5>xbgC(+-;{dsnDFjquCF#*>!fU-<54eBYmngPr zTyWrvii*Db%_t#NuemeTb!J;29+Zbp$euE_&rG0V&*ZW<9njvH2J!w9XK75^E_WV| z5Uy&}71QM81f!1QHH0_;xHxcS#T>3YZE-wtB-D^?^Ax{ggj{Eb$h8?AZP}(Bmg%ux z+!aeqo(*%p7rVofxPKp<7V=v4DsBUjUFk?^=KITstwwNQBSOc~Q-7qYYsewMAaaz( zZ>EHhD4#Fis76HcwIoBj1T@Q%$PIUK&wcpGPY|M3F1(HsY}O<$O(f-k)hn%Sc4jb6 z2)1XWvG%e0wiRKGj!A){@?o*2fqNaa_jK3Azp0#aVT#q4X`e`lvOhYXtqd-V9%*qz zLO>#_9$c3vaT>c5ksB=_u6Y+zSQM`Noyi|rN>0l{Sb6jfeF!nB?ot-jct%;-uxF27 zE!Dn~Cn8O_;YYhSpabHM=q6&G)z7QVwcYMto*wwxl3BEW;Yll7fwaqOJ+rHzW5 zo_9;O|2U3~t^SYA&;w+{D8vtJb$c4$PGW?%v41)|M3P@t|9GE#ko93z@o9o_u5>_ma+Pk^AnMVC<`IMN1q*Rl&w26P63s6ZOf|&4@n(T3-G0Bzr5sMI7aw(C}i7LJU zL3X-hm-uqH$nz3p><)iTt$bXaPX@Aa6l>YU-@M;cMNywJYahgq3!z%3eE$--9M`NV z4=cy}t2lQx*Y*u8ThP7qG$&8`Y5@JGCbD{qp|iTi+?x1JrV%`20KbA-KQ$j>>jySO z25|3dkX+K`I;iprz4lOi2?ejyp1ui8Fj3_Ul+-{V?qnG-_W^dHz=&xyR6>rp)2u$` zxN&M!-;H_meckS-W|dZ@Zf>_P_BRwn6P8akgjk*WmRDhO_Y;U;{duqT zAxqGAlj`-_Cpg-mQ@v8>w_BQ10&D9WGgX>rn6R9D2Ml|Cc7Rt&l|=U-hrB!B`e17@gdY47@>-inI*)4-FJVef0mE-Z?kN-|vwOKlw$u zX)(ytVXKm2Hx8yDkE>37nWgbw)-^U$VR;7{kR16NA|H)ki|`>Wq8{dpm6IgUKPx9Y zx<~m`h;8EAJP3UmwGCvg6!sAX^QJ*4>n#*hr`{TL4K}EL%M*H!{DgO@%eeH(^Y@{1 z_Z$lm;)+CY#d+jmTNi)LSjdMsyxFvs_cVV5vu0G8FPA~61P8r`(a9~@kxOHnc7DGW zZS)tNxtJadbKRl&m~sBZ$<--5EOaMp86cpg)2%U(qb}aRn*kUJ2UQ)xPlCJdLdKe5 zR6Sm6EgSc#X_ZR~auyhGaJ5`qiNTbL20s=aCy?8piGG-vWfW9Z!8Hdz3W*91r)!7} z{2fO1S@*Mj5UM?_C=G;q0lauJ@xUBTj7r_A)sT&#grr1nA)%4%t}}W}a&cMqY)iAR z7J6wBpc2@5`#@+N-8a^@>lp*MOzuVnFp8`r z4x_G>JA!d)bllefNkmGAEiE{bfCQW4KnqXH6=L5Kp24R4`)s87hoz345J9FzYT!C; zylGQZs)G?lTqPcP*r`H=EP*zs$K{|JX;nTO_qcjQLLn9s3Auf_^_~h3Ry9#(D;E!# z7NM2~$=pg=Z$v0Jk9M+REW_V2be?&emeNsK>2My!pfUMA`Cg@vP?RiJR^3O{p1aT4;~4}(@p1N zzUqr4ePV9Zw{YLdTR(6b&_Zj8+%_oXNlJ9k;`^Cy?D~xK_Br@pKl__-u+{~-o$4v1j)~SPhQ7O>Ym@xjHF0FKvztU7jl!79tmeV#J$S$Lfm4ZfjG?};k*kie@8g9** zT7z2XPGfofX)(-g*r}8x=SU`vQ|AqEU#zh($JE*Y|Wzo@>c z#o{%L^Y0f7XL*;HwKvRcF(*?PRww(UMkYy$jIHgVHdyt}dp)H;4PHWL@ZPZJDa_(C z)zsrDtjD+|QIlB;kDvI*2XE*4`zO;TRIYXg>guL^=jtCzO}e%Z#E40>+6)e!!xbsn ziqsf(0G-0FC6O@IURknOxNcyCrR~-aQgj{^qO>+sDBxFYAeQyonj-xRf(Ig^55!W0 zpSx%5iy6GE8-Hr76cVfNfM*Xc+Xae*fiWw=>qkJ#%~5-}P9O2pADAaz<}YfxxWoE)N5q_a@A|Uu;Z{OUpxFsi>} zJy&x_tl(`wo}qvKstj_2#D<=29Px5TpLCsEFsLR1fa`f8Ya*YRjD!X?Ovg3rZ*mke z%G>ZzS^%7H-0;f+mSAX+@NI#UfmsZ2h7@AkZTC7kDXpyng za#JK>aR4@b2As@?Lq_s&jODeN1-J&c7-u}KDgk@QQ--;cvMng@?xEa~yLgOCREHsZ z%qNFVm?2KNUlR%9I=|#S-t$&!?h~&8gPrc1W6jS8)tO2~Q08GJUQ^I8k*`-VA(UX% zFI{Gx$BpJK>Bp)nJrApO3DfY-Iu`d@&Lce#-GbXv)if`u+Mc7@lXs6AEFR!ceX}X6 zWwS?$V!nm7S{QAhsKFDS^Bg5ZCQzqNt&M&Q<8?ivL+*rs>#z zwO2)>25JrOY#Og&MUW{Pb*(CY_r?5W;%jRM+JEPwCcvCzbpP^I1~3YBp1P#Kk@i() zX4^VOAs;E3Ln`T~u^Q;?L=T4d7o7q;cAuzx)`LaB%8|OiCU(cNh1@Ra?gJ@mybkD| zye*RhH|RP7iiXC=RiSP-JZ9rjGd70X+3>2a?D_MZrfbaS!i{G>uWdTSoY<5a>KfXn zdS-Kji5V=J^B6jI6Ib(ibzK)|8~!)20^uN_A|`JyxtTdc;VWPE3ojor%i@qTlx+|$FA-6tI zJL$a@fe?j{>~NN$5;$lb#adyobC`TV|HPX_?(@B}^-%>qjLIswOR8p_uK4n2Cz`ooAB-hE=fwQOdO&l4 zf!_*fO==)Og}~4~O2`bmUx&P}f!rH0C)yksJ~lD=+EGUUU0m{A*DDB5Zm41Ze9!qt z#AQY61zO(%PRWuTG*Obum@PdL6Menh=ZLQ3sEhiqpWrbR&mMdB1kS>L{3$lVA z6B->eda4 zW%yPB6ceT1Ezov$;+dYqYWha^@>gc(x)b5zb{2SW3!+cwC1>%N+t!Yf(UAG}!?kZ4 z8M=qZ5$snsN6`IP2LN;EWySvaYq6MSDeoEkPj>V!hL=T+iksNst%vofNbC*3B6g%J z|3fc3ifqsQGL}1dkC`7fnedK0K6FwWsIX^{NP;`K-+jv+fOU{JU@ql zf$8a$3a-|AO4UD3jd|Y@Pd^$;!z1w3Xq-or&2ri0)4i(gi-fuF$``XS13fW@SnidE zNPk(8X}aHwI|-W?8Ikll4ni*8AAOu~xv8}5EwPsE`jZmV-c?yHDxsFsqry)Fvh_hG z@^ugyr}~`KhS=9^F#3CbT6r`J8^{5KEMP~U5l0~4ydapw{ENOi&su*+G^ehas8-qN z7i>ha;t?e}=}~o(#fa3&UU=4q5N`oZaV$Xti-_=K20PzctNClZr;UwEh_$Mrpm-Sc*$b&B z$71D(b$xc$Pk9ci{pweAyMZ4+5b{rO@??iSE3~ww4^!Taar~NfP#V=8c%!d)H2`uf zFx-=bHajk!{dpf0bAIlINg-^NaAScm(t;~_5md~Hk;oYkI~+4v%8)&8a?N6H(=4() zb!?689}?^pI)6yM?3f1ae0|%p)o~zPU-Y5x7ST93X{C9SdLI*2DY; z6N&br4z7t^ytNH5PoX_Ca!RKMZ&l$zSGni6_BpRB1|)Ij-hWG~4P%UNVyR}s*m(wv zY6W5S^#%mRk7ZK;_oMC6*oTLQub=SsDZZLWUkVHPucS|AUHU8bVGggb^#M+=7k?N- zwnwFI+!91Z!M7IFujnCKf1>bx-s3w69>06imqzMWjl~&?R(a)uT2;`8KJ`wj&56Fr3Qa9P@Pf2ruP

)S|ZXkzfCuaP4Z?#z@G>$ezY`c6J^C zE8PYQO^h0nYjLZB=80)pE=kP3$tKZ&%JXOsFJn^^g6!UzjlUCKYeR7ZTO6&m0U9=6 z=0Kw@2}F$gc#WRH-AG~qa|F`Be25)I-DZ?@yY53NaJ(G8E2sx~SKmDW>;<|`0qsff z-)n`~KjwXqB}ieMWx!Bnv9_1@lfRdV3S2d-q`tCh5Z`pue9o=og6Tm(UGuwl?|^Cj zl{I*bv3Sa7KZ{;fiBMcgQu7;GI$B8MW*R1zl2O{6sSl~*w_KxJNs{=dVe^4#_i<`3J$DZj<->eiW`$(VoxdY{nWYtbm^}E^EG&=~Mfl}bc(`r)W zr1Dz_wGc&gn|Cl?Gm1ZMeE(yrb0uTFuW}p798EEq2X( zxZ0_)4=GmgarBCESb817%3S;yLsNYZ3j{?hZ{ZW2iOCId2-8-S;O2PpcyI@ExGhPk zrwv4s8eKkr-t=K){C2WlzZ~S+cI3pl-{xT)Rg#|JEr)dw3Dw|z@%6JdLRJXzK$(Y} zvSp9GHXgR0PKD7(Dl!j%Og@B=8+NNVGX?nQ!E4fEC{!(2e71`@=y_A)oiE=xd343A zg$F!yi1VCF3s9dVGWNOSRFU-{cnj!?8KC%4$4+q5QO-@0D?x?{`sx*eCKO%`>Mqtz z!T)1U$wqgVl~#v6t7PfcSpS9b^4ni#53ih}fzwmw62*E!D(QSdv^fg(+iy2Q<(?8- z!Uh+e6g>zdNecKXzk4lpW zns%_?b08VQ$qnS`&+sZWuxJjD-`I}+84NB@8S`ATFMD)ANySbd8ixg{ZADWDH;zbm ze%TjFz<9sqr{3X;ZC-AnT0ulS9)*^#PXq4pO6ccZc~c&r9n^=#P=Ua16sJn8-XHl^ z?Z|HWBLhsWi6&WC3esFwu02#X~l z(}6XvKjBI@`<@-MX#x16FKwV(kChuhqgm=Y!s2Kq3q*!Irt&jx&+ECuIO*a_n>=s( z8<+tKpM-T>8jikhK0>*lqe|vf)2AIpLo6p zZz9zrt4SrTj%fZa3{M-g&E;Y?vcJC*rnX}ccs@5Z_OwF;wkezz5{`bun4l1@$ zn$eerQ@Dn2zQxj{E7o^|`G!4HS@iOX2O}Bta=0w{ELI~p%=9(WbZ9hJs5ta1d#bm5 zOwnY`k{%-(U!M}Ml0VnroW8dj*laM_Y?rf@KcYkk-d^R&Td}HU*8St0z)GHlI9vuf zXNlKT>j0w>!ZpOk6V-^2Tg@*bb%af2u>U=NHbdU{6z@+~^20bXob*B2CugNt%ATc^ z(iEtyo6=ZTn4*lht)(G3&y*Eqa*@-VgQI&9Hu40AY(e{1rkw=ybVZf03K{i*YYF?_ zcKp0lsj}>}TtDnPw=4rAf2XF+9i-Vb1OIAs#l~ekzy^I|e<9xo^Toc>P6Cfvj)-Qp zHQ{>(9rscBG>LkF3#*6)M|fGcetw3#N~O+&-_&KWs&cMMPHAf(L&I){N$8cXSyFAZ z&~TSHI?lzt=v4O^JZ^gWzp~eZg{rpuihR9Jclt+6vj6hZ|2b|PyeKRmwN{%6&xF%G zy6O`ED}O#dq@K-9v+VuUMPdBqn>pI+tObA5M!a}v-POJP5u9q9B0GGazV>j}CDmo_ za%;@|N4>-GbT3;i#uMckoROJhF>KedY^-K`3Cezt~#Jz=6pr3@qy|%;%$Lj@0qs=i1d>H%Ck&a`; z2}wZZ1eqfewNOHBrHGz@%8wCVYJMR?bJWbV-}PI%o?{t{Pd!%CktHKaRSOAcV%Ma~ zQeTO!nQH_Oq`m5cmER6VS(3uPgYbqxV8SOLp1Rwhf%-WwG^Au@p=4)~ue2W3g=@&F zO3t1=p4muW-bN)hnYa9)9Smju=RWtZiIX2mIb7DmPk9c5{+=xNZ`RTukt9nkgBd#q zmo;<5bpw0Wu{ZW(e8vt|9fb_v{)~!Z;9K;N3~d6YI=}G*9OTzu+x-gNJ=7!oFlXPM zM^c);NK@?*hCN3owG^9}u>E&|#;BpzHvpLKEdbh4Dlwz@pPbSl6s>ccefK%rpffR*+!HWeT)A;L^wB=>y((jM$0PmHT0G{|#26x^u-NWPQ#r0VnK?Y&f`_lR8 zx5g7<@ypdWVCCwS{lave9@j4AzKHaTJVH_Bx5p1lrRkt`Yu0IgZ1P$J5A?jqs8T)7 zVq8QLFh&n8``g95^KKqVZF@No=B%&*q8?vVD#?#LR-TwL#c5txoFX&pTL@cjKI%+E z-`Q7k9xZGtwW9pE6wfVLX(U=1k}3X-#DrWXL^n|-A1L@V-=)E7{hr#WKy#;XCs2p=-JKJu8*W0F&*Wt`GiHLXKMTtU3$kzwa&8*kOP!Q%5 zi}|%qW8HoYqP~e7e63q7Z|iUXrr{P5CK6z5dIcDzPueiZCqP@`)S@IY__xl`b$-mq zs3u6HP0Kbn?x-|Z^cn(l9@MQi8-h3k7Y3l)9ViJ$@pFEC(P?Fk^i>&%rz;Yd!oot7 zvX!u;$~fLi2W|Nkjp$cFmjT@5z3AB+%7^J_B4To`8KRIIdI0r&2+OR3%M}R!bNH+e zUz8R!HK;kA-B{u}uXxer5;|XZRly^vl)d;{GBT$p>U`o8jlLw<=$H2 zM*Iv`O&g27x|RMtL-fVG95Ibkb9{U`BaZvstlGZb(MsjC9#K|p!KaLPOYQv8w1T_kW!Wpir*i@eX<8n;%PR4a?qJ_hkWeU$s@Aju`X^BWp-?>AYNzDAII zA&sDJf;fhzuV)7W46DfEdwb!Gpfae`1bKOdr1+6!H1!#u$XKt>aX67cQ z*y{=;0$~kPGuN(dM(nrR^`B-ovOrlphY7>%$erx{DqqsO*|T>13I17`AM=67;?f(t z$M!D~rFwuJ$o);@)Ws7z$A9Zf{(OK1w#3BlKlVEwQ7Uxi-Q8C_^9oB2^0K?PyxC(w ze>Gr{8cpFJ1K76&tp-0H19I&=fY2;{IaF-!?ahD8-cIp(er%KNy2#{Gkyu3amgnHe zrzqgpvcFj3>`8r*OMUC-bnlGotmTIBX__9qvLe}z>XE^SD{!RnQ;M0^CnDmx;qofh zxb_Lk^yFBavfgnY`Y*-I;pHNjQp`-FKb^F-=T>jO+@5*7Zol@Z1-SIN-v7s1?bu&C zErDoSZgd41v)V0Q!@Qj;7`_1~!5T1@ciLz#TprP%G!=FY3)be5l_H8<(-H@jSCkfB zI7K-7klNUw)X>rhB;+2VO&ZVa7*A+^oONJvP?Kw{Y5k0pRE#e>3M@^&l`r}fF*xOy zjN~~lwVO29*Bn_`he>KXMw~B^&JCvTBTYbJmYFjrQ0!_`VNdJuCX~w+u+oDV&+niooi)+lqf$KYgZ%eotAU$I3o3 zYy2MT7^$|Ci?y?REDUPWsKgS^`5T9dp$eCq)vWKqN)kjF1k!j{GbP=5_e(CjzVvT& z9KqZ602N;x>=tff$!`{NpWUnB-~OB0uH~;GjIFhfl2%S+;Mx4K>{Rdmto-t_@#yv= z^F#6Dxb6MM>qIxwW|GLs*BQIB8rL8eWQBM&?R3s{58KH82`p3 zdSPk58jJUI*1Qg&VfN1%RzI1+mb#S^hqgCmWtr~ef?iTQdNZha`y6s)A}qN%sY?+2 z@X{ny5p+cn^-XdDO+}?O=xVz$H#ZTf*I=D1gwNSDcgOGRG5QT90&JFfmoY+;CA}@H zfHtuLzi;qk-k%bHgOjZQ6Hj>eYbj|srtckb zPOu-8Elv6VNIJ`~EVH%?BT6G8Al)V14bt5;ba!`mcStu#gLHR;NOz}zJajjr@8^c{l($R4WpQxjZzg){C&5Zmub!n@-YhKk^dJzN`bTQx{o-m5p!^%K7iZ2i6)<*vI3Lu~1)^$>T^`x^xDND;1I?h zVr%?^e|;L@yZdSEb9C+(rT^ExN7l90Dt(Lz3c;{)UF-))gt?#Aj-&=t#ncj1bi_~v zJamqbACX~NV_ntWqwYBcjcCr@rc8~n$tp)dT+E}cv2IkhBhNyuN>{=`|K|sVjxhrKCy(mEYw{J`+BeLZR4l?) zf!|hUv%88e*5#q9Uy%ZRAjH=PVBHq16w zo7OwcKY*x{th|CVVD6z1as}*i{SYBXR(YAZPm+?!-OFN5N^xyI)0*B5WtmyVCgYC> z?i?1yD$>yHiv%)@sy2sT(EeAS{h`w_?be#pPB@Mm#g8dmMOH3#N6(1yZWD5>m&Q=c zU{*ChvX?cACVVnB5A9pwu53CQd%CGtAt<4I{#WpP8FWHg)p5s2ONq8pFTFU~X55s+ zUnTmTj76F+MRoNok2(3oFzIJ@a9=&1&GZs^DvF}UO@HS zYWEDy7)w0<_P-z73yKgfuRRbVK^6fLP2RJ}?zfj*_nvV7hq-@W^Z+7M3s^e z8-2GvN0F{4%G@)!deo#6neZ$dDRD-6bV8Eh11acyV5+p%b5gLmX%-S3NIGl=(F2m9 z<_C|dVhnyO3Qjgmx9`Rfgk_r1vQ#f)yPsruCYV87D`8dXesBaxTFPPfS%|6pM3`g8 zOq&Y{=rngVUmJo<@XfijBYifRoJwF3CQFH{#(b)cImjou6Y}gHWmHRl=N{erU~HRnga;*f;8^ zJsT1skFDx5r1>|2K|X4iYt1{Oz^^z~k3e34wddTOnqG6+>Xrw1Hr7Gb@b%|T6S&+-6}eeiMJg8huR9;y)t6vQ`y?>2Z;v|b4Qp4f^aWnjn;X5Gu9GWE zUMBw;38t8Odj-gUph}7!^)MQ_cj=)-|FVY8Lu;z@#4=K5DJ3^(dEpqwCw$zhP&Jp4 z5)n1K_(%4%m~0-iTwGduH|2Uz-!I1*GHEpIi3;9CrMX^FFW&bm_Vb!Oc3<4LygAK3 zPck`M{z$G6{dehiTD+v;Kj3wDvLaHf`YQwcR~r}rbBBDz3aERmcia_MQMPKq(qt$9 z7pjB-H#|ybkCj&KLbr~2IEBhHfy_Eglty&O;9s(p)E*EWC&(Ms>d`hiDfdQu5exY) zVtC^N8>=%(Getsbul+!zGv=w_klLH?6?&Pte28+Wh#Zw62|@#~2$uWu82vwMB_>nK zBIYl(LVtLd?T){fkQbAkLcs4R)Eu4Uj%~v{>fS#45@aP+Qn=5x?>eC-VX$d8&|R3y z99(q2dX)T!qe|IE$Ji{B9!4t*nXlOPx|W0(c?M2l`9Fctt|fcUo^MTh8hVD{aQU!7 zS-h?RcD8b0XFCOUwv^-Fo6G10kRs}lq@g38>O=+LW0ioA=jN8W(cyl*Y#i@6C&yV# z!N99;P^9(i5z;NfaECiuFV+>)r@Z~k3rZQf6+{HUkm84e&og+kj<1A~aLu>rd)~F) z=*363Ve)SsjzW42`@Y3;T$G|Z{+J?B8UJg>+l^aT2m7&~9Dr4RfU z#5^I8Jb%KP;Sy5Aj-uoT`n(47$$HB*O1JaP*!e^(eUFdS6u^XN=;D&BRx$MFkB^t` zUBfgKyhzGN3wL5u=)XJ?$;$+TEi5FgxU?$%()M<`6cPi3)Kz7iTI1vFiZt5 z!b8FLO)dK31!YX#9uXxEtWOvvHyj+cTrq?LWi2L-ouQ{9`N!Io z#l|&)_nL*}p1%dhr7415#@D3_J$BIsLuh2Hq+nbqFMC z7>J?%z^(V!v1Yn`X`x+TYPV*sg9=#$ME924U1`rfhIwBdc%j05*r`K{e=4-l*Hyj@ zANaogLo@}*PrSB$uZp2`#<{6pDzr@8E)y4*g*2SBfg=ZnfV)317;cW^ z@7~nOq6ORQzf9iKeCaFva0IOD9;>#V==Ho$n=t6wtFw6Q?x7B@u_8zhUQmG*1nFn1EMx(CR7j4~=Qs z1_tAbP`E6eeKZx`m`-xBS?JC{{w*c%KvMA$UFHNwlUEWkJQbERTR$SL_&Q3f5`iEp zb*!SnO3-5_bssl}Wk$t)Cv^-eSR#}%S|V}}rQZIiTkSuH#n*P3!k~u_vdQ>V0%1=x z`xN}U)u;5oBZZVN^I;!2V?{`MxV$Klc`Y=lTOBliX+^3p?s(4M!B|URq|{TYhLt0d z?cUMTXQa-%6mj`$QaUoPx^CPfqoDk~yScgf91!u_76-p8w8e=(?_c<h1UfNw={ntDYRDqc&fW8nM(FY=eOPIEio zR;1I1ddC_I!&uL!;^?i*lja8#-u$PO(x*Dy5x;8fj#OT|o}6F#Bv!Go!+QR&mq9T< zj}U56+}zgtF-n%RCaFg{oaar+xRCP5*!9;@)XOU~BLgRSu_U?Kkqn5X_*@=eh55H& zO1uK4FvLI-Md9C#g7fof%k|Y5<8>)0c){m#2ykl4?w)kS?`P7Py{X&!)0T_2k7r1k zqAaU0WzfL@upr>?1o8_ev-?V1-O#mekwHO+&(c&I^Kns*uY1p|)*U40-c_0}2jhwS ztU#tT`La>UiQQ$X`p_i)xe2POUUe`<#GY0`H#oyn!sUz++JSKQw3k_)!68KMs%WoQh!|8^iR`lIyZ8+6jY%0Dx z?R=$P{)G;Dnh`JTp(Ijcvtokb*pVEUtI}6z^h7NcFffZ!-&%uE;y)K0H#(rJ?dee-&y<3@L!? zO1;+T|IcsV%-r!yJV-_01&0mg7;W6af?U-0_zLT5!q?|e<_CPeDh)kuk`99eIN$1z z&#g?E-uz7eeVF6jRovod;0}-!ARhC|2?+Jd>3Y7q?7r`c4~F{y#3=9d4ihD{Lu{E0 zrjOA$v41HV^3e zN`Kt7V!u+TjB93Yz1|8DcRO7j+Io)ciQl@>={K>YOPC-e+$9YiulQO!kRcyVwp^4G&At&Mum={9{Ursvst{B= zQy_hU8a&ISgI38%)!i&WoQJL(y)f&k6OEIv$5Eblj}l<3IX*FQx%&5|^I=v-CpTM^ zHZ+R#wSd~~bUnk$r%`!%DPQ1d5dNXOx%57}Y)@yXU|NSi-c)nmid}k$v}Mzac6WCd zJjk!H7>J8a^7SBlBT3nOzL|gsi{-vZ|DV=7vYk}rtHE6bhpRm)wHm#yqA;4Qxy5+) zqv3wjVRqVw^OyBXDU-XGTk&83=-70<-|#shBl=a6WoPtzG{t7CE*Q8YK@Y3PSsUc% zFmeVe4;krsZg4#$d?SH8I_{3<-;sXQ7}vQ=$ciJaxB9W?x@{<`P8k5Go9iZa zWjf4ksK9AL$Y!3Eow(DIKFhN>J|aFU=Q?m6@+(+UxoofVmuK|J>qii%#k$h zX2Ul{mN#Y0%TeVO&4h@f&niESf|)Yg$U!Vp!H=>pZLE2tA>cybr86mg!&_kf2j)~Q zYvqxrNh?R1Vrp9uX6bg;$-MBrw;izDM!8xtr(3Xns&X?wTf|LVnv&EB$G{#zW)iMI z5gfg8n{}zk>7m2MtJmllWiBj5--!P<6Sezg=Uy*krqhF};4Auw+}iUvPqKaBlv5c;EuN`nght(!7LpAQ5*(Hn>(S zwC{Uf@WlhM5GaV!)PRBtWW>u)v{abU$x&h;+TI_E@ay`qUNoH27A?ymwOo* z-doCQyDlM5XZ(rge_moHI0&?FFZ4YcG?Bz@!iD=lw4b%*5mw{#NbB~FBUDyvvM&@m z__1?MIG?kg0-4MVVl_TFVZ4SpAo3sLqtR#yg;t#!{P{8k6{gWPE>aKH5y@>yo5E`9 z_EqEFXycDMUZFaIOLxrL%xX3=pYwo!8SO*7cdeD!iFM)=wZYO^iD}9?gpJ1L80d3B zMUTxbGE5g_n3zWo6R`JNy59~~M471)Nhg(&Vj)Qs2KgwA1hX267%_KLz#GJjeSJ^=ZwtvYC4-pe?5*ll<8 za;NPOwR}&Za1p6(lgow0LeT$}EY&3HDKNewg|J4A0kQupdxhF%E~tX zgTi2GEX}R^Iy$7WdQ4`s$Vg*>I@c@RNDZz>y(L%8HYbYU1saJs!r$O)YONkaV(c2s zlmYJ=Cs}#<65-=Y9J8M4fxSq9L#7VG;mge>u*)=SyEWeT>XTyBc5U*+3L{aOo2%4q z2)qAsgUaiE@=b&0BlXbDiOukLA<3de8^n@U=UwO_0&ae9X;w9~x`dn~>U_!%@0G%< z4iTIFyE%%kh7D_n(*02;G1ycSl7NO|$c#Xn^ngkIMomXvN$Nf2E;bbll%>+hIDGGW zBw_J>AAr8#puv$xn?(o)=6xjsu^taoA3u zadVM|=uxzEfShj7On2tDz_$1l7Fpe;X zRwYUckH)iMIC9LZv&F zBa5VF6cS-jt!gr){hM-X`*R$(d(w_cbp%05deNBo`2c&T#^3Tf}M|)#`%Q0K5kt(H3l3oj0>GKEEsUe~<2w+ir2%&ed@YG@mB3OR)(Fp{Coq8xV8tYZdG{i13sMN;@S)^>wSEVWL zJ+RVF{G5iZKsh|iD)HQWf8TCwj@4Y*434fPEA|4aoqV{>v1dY$ueRDPJ065p8fA74 z5uylv7OlOpO}>>?FWmnf1E>hC4@CCoBL~LmP~6g?QT}1al-9lQWw9n133+Pc?7i#n ztXogpVW@h%!H8uFO>$(BaWslYUFyPVJh8;c&!T5y)LTXsru_rm$iEPo2yVd zrbVPEewR|g3TftL(=E5uYP5M#7}E}GaCaw`)2hhI%BAmzcnDx^z!}|@wcOx}Bd(#< zweom(=CID%HD%;zf7`TBqK07OSMGS)@e$I%6q4Gx-;+f*(XweTj-ilI!1#UB(1`fj zU(0MuB%i}hU|wECE%Po){@H(Lc>YjTwQ)7E>KI0wbJg;jZA_s>vz)rlP9Gch`x<;T z%V`^y{ca)_PW?hX`-G`BF1=7Zdk1VH=KDw{woRF8TF{yk)ggx?J7;BhV;iYPWBk1W zBRM*geV6C`KodRLiCxofwm?<+0y~`i&t*Jo>c}8e;cua+YW#WrjT?6V{=*P6Ps{(w z!u8Y*@+YoCMwj~PG%5eqTsL?_m44sCh;<1MTOZoiE8KKJFQ2!;Y`Pg>&ng%cIRMd;!OPIyA$dXF0qpKvDo>qNvbU#INYO zN&*I7eKXahe|Zwps#lu;$w#^FCs^Q?F910Ge^JF~aj)LDHit{n>fP;jJ1xwy)LOIv zv>~C!P~kwMx>l1m#tsm81)uH{w-73T$*FKuV*R8j?$fi+qC3#=>UP~f7w(#*=iC?^ z=6_PMYdfSIU7%?a4<0$Rpj^!p2a+j1-P6YB z-#Y%}LTTAf#Ki{HeN2ezhEcRmPt1%P%e_W&_!G1+!ilc=k8bChTzTngQZXZsu940C zq+XMImYVEy+)7n5rE-zM-SSFAH0bjyc`GOOu_+X`!TDMeK_qxV70Kh-PK-KD0}(qZ zj0sKj``b7($R|bu4q4UuYt0YzB)w=+W@91uC@Ji@=xK{z8+`}ZLKF7qJ^NBL;fD3R z=%u7>0ysW3uRm*7Evly|CyhCn01cx&3)QFyxHx=(m7N~gqEUrgmuT`#UGX$)6LdYE zGj_Xhz5x*oD4H5Qb_7HZy>P9&lf0TuR-Z&f26Q@oGFIBSPbvl_i;}C4o%T;O0Y}Q` zw{%#=r@wzv#%xBW>b!b|>XKEPV~Z&foLkVVeHr~74KppwW<|Yk4#K;!+|Tu@R8v!= zm(zh?`n3VV2}0mr>o$R_b;@Brl@qMNx%>RL0BylYO{DlK$JKhN{xl2^n}|pPDvd$k z%*iTB28)q}nR_Jk8ZuX1&<}KL3<;xWpY^q895LI9?12H*8 z@^YnK8Z|qHA#VzW0b|I>g!kQ7T8xMthVHJK?$PNBc(LJ~uzhYfdY|CFJ9M*OSPQZp zoH1z>6=PAuA7~IgXa0LSSiq#$${z7zz73!tc}iX|DV5WA8+F|HN~c08jk(T++mA;2 ze(1D2u7Rywa!e*DhCV>DXtv(rA_mlcnh9zh*I7 zIqI@Jj8e;43EXgp!`g5UBw5+utH~mhixw8?=Gi0^2HFsimJ*ga)lH;)sZH7Qrg~at zEPRx#zw{tWrS{Ea)qT2t{38G=EP9frAOfTzRClUhtG(Y${p}(uoM*(`i?x%c2BbM0 zTJ1Kao!>$ERJwIa4f{u?V6v!$3*JA;L2Tgbt&+ z-s>9t-#;9MC=fDa^JbxoGKp*Lwq-As?o#cF^>jym1fnr^KPam|mgZqi-Nvje*uiRk z#Rwy*P^;dnlOQs^E|CLSjJdhFY+m=c$dM73HwUKH^+>_T?ckawE-GrS6$Eug%@ZK) zL6s)`u6rsn>2n=jbf{MB%F0SLj6jxI-iE}ID>Vk9<-4D^+0G>ICd^pbea7A5De|^z zqUq1u0apgBE!yvF%dflUxggh`cjsGEqnD1raD>V{@HlGyoPd5Iu z|26EtuSL=M6own$0B@?>Sy_edr`U#N*Ylh<^oib0HN(%zBZrU!SHY-Y2D+91%4KBM z)WpjOTVffZjlZ0zpKp>ciK~0c(U!bK{NVGk*ySVg-}|U`)}3QSB2lMdV&Vd$&0)L0 zalaXTx(v#ELVPxlJ#0RI!1`iZ+c>9a@=*uU*Vjy^=lAQ=qK(EtHJ&>&KhNaSzpG=) zNlIlIeyUq<4+OGMQ>j1AQ{yL{)cOA*f|!S+E~BaI4k?(edn9F&_W4q;qc*fn$3qUV z4`}x>3+5$8KWwj42sO~FyjONdHy#%f(_4BXH#^lze0B=vxdn5aFbOHuA|Z>_?!9eC z<4?q5%`O!xg0|8@u!?IOvXgMYWm8ZGY3jxSdsdn$m$+4bm%5JKSNp0Uw86m zP3)&NF2xZr=L0A(@$!5gt1ufEYHt$Wugl}-0ow?k$I_`wi* zoO^qo2Y+~7#a%r@D`6-Dkip^GDP`}M>tvfqiZAj@!cO&hhMPvPQt*BAH*B=SKWYiW zeM=egGaF9u@0qY^g`GkrEBBRuy`0pnPgvUHhYn&YGN?xsL>LdpfdL8g&9_QIbLy#- z<2N5xdN{S{?Uw69*(=o1LrDODeb+i(U@}srR2i1mljRHsSIXcNxM*>7>w;!}8BXT% zh99@f%F8LyVE`2{o69p1-2dQ)ADuOMqt-lLoZMeeCtZw|3(-|kZ&b}-eKyI<;g!l= zC&g5v#vkr;)U|5T(!aAPciP`UOCGX*zHhJ`0Phx9_<^s^kg3bru^K1mM<(O90~V*I zZ2URck?)Ax;tZ~9w-1VT4)8JX>);jd`jHbfWn)VxZUyorsoSL$zFX_zbtNz_lgWj{ z&7w5R<0vpza~;{FnJF`k9>uVbwBc$c82QQ9xk_FMY+7IUZ4hQ5k|0f5?T3cH`@Zl- zEiPV#0NcO;Y(cAjfC+8{;zUr_nv8R(9N#S!QO%+$p+F(ncexbb;5Mh_cDgA>t-rGZ z$u$LQQ^}#YpVpgIcH1%)1C6yy-j%`#5gY9*vvOCh`0FHI zvuOHckfao__PoECU2Zlp(?b&rnuGirH;tsAh(m8MZqFj=$Ry8)Jn5c4|7~MJ&eIR0 z7~4L0Z(n`v*Q!Nl_5?lMbmfxgRL9l?C=efC zv|Xc08M7$1n3QF5K7heQ@kd!`4RH|vs;uZpf$l0tuez*mh^Aa*u?Cv>UO{h%bEO&G z9)ZE=wYGysF9vv36mxC&&fl)=;vh>isVHuA-Pw705WvgPX>$r4p;dR#x&K}{JSq^cJRI+QF-?-|{|lxO5b$b{B6#AGph0mQxX--0&eHL$TI0uR;kD7 z;pKIidfTu4+MC326qjiY>>JtcH?3F|fgea2p3abG2e(SJro=KlGwptYnSHHDi-Adz z-d$H+s;!ZrchzyZT?pNBmz})$ah#ZCKVBFpoS!HA=d*t_87r_gURFdwj1px&hxB5a z@k^7`7MU1L7947O*f|LtnykAv6wooS-)FxoP6l|01wT8PNE)>(h;a0TUn8~gd{0!In;xM1=o9_B(??CSxHD6` ze`yF16q0Pikn!U4TN|p?#1|D3JN1({zJbcZzZIs&nFIu6$Zf8Koh_Ym-yfgv?JO7K zkK30pI4@J#P=j(3U@Z#*y9X9dPIFmQ>({`x^@+!qo!jF#IV)4K$pvaPD)wwK+uQ?+ z6uY?x?lx;?etx;Pc#A63>R=X!GC0j-2NWm}^^VKq%kZMUC6vI#ppezrNd-ajt;P%O zVMpau+K-0%@n3mYT11T(rhI)I;ePF~q(M9>GsWOv@lmFl0E3LlYr)*K-QXKa4slUQ z6m}ElK-bThsW*W1vgxmEk*ZU<*gd6xJ~+G3+%P0-A2nIxGUJIBZ|+Q`yHnP3JS^GO zz~>AkEB<5*3c6}Kv@ThTa~QBr;sp6_i!5m~uQTJ%lmF~=5S;0ltK1+rd`l*s=Ds>| z{oX!E;cl9?)_nd90JX4iuv{(=Ow!hL+Ggps@30S1;A6!4lwHzMc1vu#r(AUzvO5BZ z9&FZ{Vu5_%csH+EVqRKDfcL4KO@P5L5$%h-5k^KbNZSb`(k>E3%BJd;hD03n7NBg) zS8`%_Hw%{=3@)ddcH7(WvoPZ`2ef&>>{~&v$rpz3dKHGS3*$Lp|6>T0R)Q}K4$5-Z z;F8ywjw+u>wU5C9s=HLxMAFn_O#J(=W03YnE6o`VUextgoG>`{R16I@e2OAAzh!Q? z2~2#hR4%E(I#NqbCD#;O+YE#Yv7*f4Y7e}G#oq^mTM-p{AL@J~Q3eznwW^Z2kqy;WFtYUy*4Ayk7t|JK|-(+q3t`u+t&3XQ( zZE&|oVs`hJyKfK)z9Xbo+N47a%{`?aE-uX2nPju6<7jSZp-y(9tEx8-iA!@`&~X<< zXYB{(ewg3>I1UN{-_OB8QT4;o=2Ni~r5Y}8>Wu+qr~|8QY9zIKV!EgTj9!miiH4OT zRhmm+TezBD($hDTSh@`8RMA5OE7PDI5COAdfX$>hO%HZq#aV#tg2aYycXu0%18M zkYjUsU>sBJanb ztr*6ldL^`|?}W}T9HvsgX-+n>6L((2{xkM$L%3J^bhF-NEsnHyW@)^E$DLSy zVE!Axip4(HgwH({*gBXAom_ogu~Ns~?}&_=G@EQKVmi2t;P2|G>~PaL=vq%#DX;nM zq-`dmwL=coGWIg$Xbx_DVE+!uTVCeKFg-*GDFB>wTh>(y^dgC-4lY$N`(Z$590LFn zPW<5&k@%VGtV;sT38iM_*|B7kF&uSm)Y6jDl}1N0qUVe7w%s^hz@HqbCkRrD4xN+8 z@H%C*)PH~#ZiVjP7s?_+?w@sO$bof`h{EsD32AXKyXlkv|wns0&)PQKviEGt_`x>}-IFJw+ zt!mjE1*py;;RF#l6vw@bkH8eg?QwvLgoLDCW7GaK8|9R(oBKHry|nUrUgyS1DlV) zFF$F|iwca@cpL%r6VHh#(#5CCV!G&}4ks}N-T97mD^2!YT&2fetmaMjD;hU^P!aqF z)NLP{)=rDw)x7x__KOotB|Um!WZ)>XLjHLK79;<_Y4&f(b)zE`_3l2H`lzMMd~Usg zTWx9A+654H`LFsuTtzDQ1mW4Wz7c>gqaUAZcM2@`RhZ>^VORXvPk7K;q-*RrdO6B#eA9%*X z9j6zW@kpyz`%+_<4q6>5*wjcnJly+@tK!P|kfzb{M#uR_H1_DB(~s>eK=e#cOPWr)9XX8)jbD8ez+Z%RSf(O>{Bby( zh8(ew;X@5M69?_+ndv{CT^MDHBE{@Bc#%(KspALp+EH%W=%Sfw+K#`XhIHgInY8G? zDx14R?q9nQ)n<=JcG9-Kh$BrMVotUA&cUP^M2F&bI!O-cIunE`m;{HU6yU(S*(oD` zaCxgs4P!{GB5|XIj)Koh!5Mp$>3`@W@7~(tV=HKKKV`f~UubfCwtOD2NDN>9As)f{ zW-3KFJoOh4vX5GrkTDTM^D5LT^1uY_D-3`B3=>svP^O=5Q*&|aHD(E#0u7g{b-8lk zgdGmF^@j!i;J7Rcas?A_YA8ozDvnBB2|L(u45sWHg{9!s?moZav{@O~y%!Me*7!Bv z=8O?FBo=Lf9R_q~V3-_#7)`0v?MM|q>CQ=4x^tfJBP%YmZhE}0=L5#d*DQ!WDDvLP z^*+m2q;fc0=jQ+SICX9R@3iOl&jd0LZhIwehPBMRn77jikB$CZiB9!>?Jt5R=UZt! zAL48qYHNE32j2nFv9MdQFq1X2;M)1)nz(J$B%cNa0~X=F;BP{CZ(~vT?1%4Jxw-o{ zhjW1SQxbGJ>0#Zz+Rz~E$1=GjT;he9aJVC-XWSXY@*}`8gHC%BDm2RFM4q1YY>ei% zR>&o7vfd_9`OT0~XuR)<@p`@a2R+xXCHN*qz9>=zBu32=El^m>UE?tD@)3^7Y`dBo0ORLjUl5j!PK`Y+}@rU7(# zlX{CW?}eBd%a=Z#3bJy)EuBQ5guKh8=OJmpX{I}rM8~O}dDA$31(T&Va2H#@`(18! z0#T_*Y1M-^rvu+{Ke4wC#*)Sc>qfE8y2)$`b9XK!2IRTfFb$V+{#~oTGiMC8HNU!e zw_!ROk~5!i#=kMT&>K!T}5^2Qa|>Jq)GDie@v z0n%c+OW3Zc?liG7can)zmdyy1*NpAxW|xglPj1TYE?3;Zo^VozG2>T86u%G8@G03t zvU02&akU4Ik&}uuk$u^inN%?#NN5U)BS4Oe0jhC^n>>Zlo^XC|iCmUOiydIzr}*Rx zlH{3#okwUJcU%sSSiS;vvA>k*A#=ADua~`c7b^7B^{ao@eccldcok}VZ>|5#GQOZG z2)wu)spY`bc17M$b2;E6hW5K=aCI+mtToF~RiC?azqgj#x~`jVt1UJ$G|Y8t5Ym<5 z`?l9FO3-f*ciD7*{nQ)WnY$&Zvdq=rII@KI9)*a1yxSLmp)(8gYD!7nX&FQgxR4i^ zXme!LtT#?YFa+A7HBL6PEm-LiWU+{f*-}qD=%iv4s1e6xd4$2Bky^`<91MwW z@L$x;>zL0yx37>_{Wl8DcpHEo_Up~oy}vh36!6~NtX=}BJ2=YzFUTe=&HdB;*MBZu z$TLl=cMU-s=ai~ygK=G040Rv@z>zOLP2V?%q%^Lv`iGXz2HjLsjNtROY5g<=)o>kFzJ)Dki?)feq4)9*zN zyzllQ{`M>QVw5c;8Y2i)#wb(2ZW8hN9KO~F+`0nw-a!{QSKMMSrAB47lxWf(wf&DJ zG&IVb|E_a8J?czdWfcu)9pA36ID>MdMFQ=WZd=~Zak&O|hA0_N&x1%!M-g@OYe%#} z9|p=~zR?dF4Xjm81W^F$(;hIb^nWVjl;zjd+B~gbFNlskG}9cn#tgxw4F|b)^<|q9zJljHq7{^I6A7efU!;W0;XZX3txJkppfg@&vgU5_aiVTh^#1Yo1OHtKD z#B9U+r1*7>2!%iSW?Gvk%2i62TMb3NgXpKU&2nuZs9l(cS#`{=PW4=Jb)=7`MMuZy zbqvaexW-O3y<1%}I;_w9wz))AJS*0^V&Qc8M+`O`_LAj!TEQkKyAW`zQZcmsIh_~d zn-EUjcy$%M@L&gB9}FneQ)Be?KYTl(TF1}k6PUPokOrQqG)8?hfLOr);>E^Zt?F2+ z(x$ot28u(SgIKP^wCj{w;SFa&Mx!1Rvp}(oP6lnaMj9Toq!{C7;)%*$ms-=8sOf0m zWS4B(W}_iQy0sFu3T7T2tAJ)y*^Xf3Fwd)B{HPQmP!fnownHrn?2qfTw(=7e(%jBH zWwh}>Y3n@a#KptIT0IU)fzyfrT=AZ7%RoH&l;LeJc`fl@gxQQ zNQz>^%v1-6yKY*cL|h{6{&Kf9Zx*NBe&~5;K%+5JsS7SiBFJ@p`C7l^P=pa@dkh9wkaBT+?5 zJSbswIt#e`FJ=J!%zbPHWfM7cvZ+@Ww+q6QxNJp^-)Y$eh7~(k%A4<*-_N zd@;IWv#?{#PIo-5o{A)S+J@;SWDJdxX05N;Sp}hkJ#{g<3U-9L%hnwK^eR&VT)VJ~syqM)p3t zc%T^&5A}|&_mbNcKYU5gGZy4EUk$~;PBxIF@1H2$W)u}5T?(0KwngL2-%S5Vy^GA@ zauk@nNTLEO;ldqrkXzjzr_yqOXrVi9XI7&kRB_5GpkBIS<1n0ykGHhn!Gqg$)_C!` z;Mlmd@lvV&X@lq!bR>}#M|IGD#yJ|;yo>5hZv*4T|6Gc2d8y&jCyfi!Uu$;h`p9e~ zCnajn2Byb|p*}nawf>}YFAuj%sLQ_RJAW%(POF5`)ru_hH!Of`tlsWBkh9dvRsRBo zQF{yV+kutr>^&NKqJ#keD$Te+&kL5_?4?$X0srAk)5vlL-IBFfoFx9GbMxqiv%IEM*2v;o@n;)8< z^FRa{>jY*!a1yYQD4{p07V$L8)jr=jvc=$B;!6$<(6~OI)e`ROSD7WPw0WL&zR2@G z92l=V9aq6q&qZW|Km*^Dv4sUH0W~ydy#4!Kef|;jaLUJP5fW!PxrHPR=zgkRoaNr1 zaqinGaIH>{EZ+LQp-5>AigbGpI*g_yqUxWMCaZ)>PBgSj=g=tA%^!_VE`6jTW$yKLPc6fUO)!Dp9DvU}MbWTq zeD@q@HTPaZqJw5+P!AckVZRAg9 zb*$_%mJDbr@)xdc4llRUce-su>ESn#us9+Rv@a#ohA=@LE_Bs64eZm$#Ke`5l*R2D zXk)6Nqx(SGAP;j>zHvZGF!-i*ie{uAYp5N?aptaaK(BvSFD8@1nv~VG$n(Pb{CBYT z>J&aE5znDmwLp=IiIa1w5bMy)y1gU6{d3ylDtQ)oA#HRAH{o&2ViKY!semRBx-n8@ zk!0mc@F0uD<7DCB5GTnSzU2#(5XZ(L+z0Kqr)bmnsZ6|3Qgm@+5$aqif7g#@zaNli zRm#LvwM#ol{Soc=b4i)r5%b?zb>+J|C|vhl(yi2KLL6(Z!w*+$7@42Ps6J+4XBR8h zDN!z;E~CHbKmPo<65TaUCa2KW z0?ZmFPIO|ypVNY&!0Gk<6AGtYiiX<#OTi4A0ktDWJ72lyOXCk`){Zp8rbKRg?aW6Q zISeXsSgDQnweARZiA*Rv9Pc9A`avs*o>IbJsMSN|MUSR;8V$`J^D9MPmvAYuJ|K8=$MCI zH{zNC1Wc#9aPjztw+~!^z+RwA<9IRdqosGObKnc5boT>eVfq)_+42VR<^xl3mRp^X z4+Ws)qkopi4wx^UU${-Ul(RB33#-y@R;*S_P-fv|9oSUY|2@_HAl7|*(f|^6(nCA! z8|i7Y-8x8;W-o=+!mRhMlaqe-&@num4@?WpT?CwO9)toQp5>nF%G+IqtcRzyk;Zr- zy=aNokf{c;-NjkO`Ugq=42CTRSrkkGW2o^ zl7URk*l^Su*Y*6&gmX)|pVf(89G!}c;0A2B?s9I7y?MTr?(xI(Xs zoRKz*87*s!-o9QX`VQk<)uQ!98T&(E{CT)&f|kqFNz0^3%^WfOY&iam+>#|Y$UHa6 zPTigzt8RarMqJ%NNj!o#uXBp@?>QhWd?XRgB~sM>iw9+=yIqpy81B_$$|HTZC1WN>ecY}Xa);|kvhn&iOv zG;p~)+!3?+^roni5^|Hl3WjZQ330Bcr(?dqgXphLUv|*T#p~7++DxP}KL$(xY1+FA zK6aDiUnM{Fb9V^E(fy;Q#5R!|$=yOTF}!l0m)da>`!(C6Vo`?X*Z*;Jl~GZ3T^JA$ zP!RzMN$Kt!knZm8Zm9uj0YPbLX=xd{yQI52rD13Uq`&ii{DB{=S$EC7cb~nV{lrmT z*rq6xte<~o9a#lnkC?9jxT*;X|Ic+A=+^0<*)8#en8l_iQ`*$?yKEp!gFJ$4E&cAQ zf?e1c|3P~4%L>D8NJ;~`{vg*$DP?c;QV(aO+U#0k7b*I0a`N5n|FZWQeWU5ZCmZA4 zIg}I>@-B9|!{Tf7m@&#CmNG>p-)F}eILWYZQ;qb0iH>tW&~>p@?&q>dRN&RS?h4{( z;fSc1P1PzMkq+3(#l4VhdrUUoodGY}j=s}QFxexyXDghPxPN%6{&VHXsXsa5N(VoK1OUP@i^kdt~Y>2QQ4;3_@tK>a#2+)Ced zuR-d4EQRStNsW6l11@rQ&P=EpzAj>Z8bOkgucTdZTv z9bKe5dS7jxFtq$%&5*>f*T7jYy3A#40sD&&gb{${4S6`lc_Xnl4GkV*UYjK=NZ5A1 zTIL76P>-?TBi|G!Cy3hpJEGi7`W5aUIYH$3b;Mt(yvV%HefD(;!+(C|;Jtp2HAixO z+tspA7iFniq{K*=o1d#|R%T?86@a1y`n&4gUr9rUi?u`Zke8UfBnlL7;mH6o(o!&L z10CKa^Wz?8mZ`T#XnHanv3db64P_T?by`H{t1`Qbz(klWlF_n8P_LrXReN_Ola^&S zbEF(!p;-oZSzi|gS}yo(nWRi?v_3&72qfR+GiY+BZ#BxL`yH-_OOh5s*SE0GbCHdR znM6J1TZ)XlS90MN<6>^6ws1yK(9Gn{((z)ESH!YJPY$myaX&S@hY=D&@StwB!LR&8)y6Pqd@#72r(rVcL46VvS$D zN5f`A$C*k60xMzx4isiW>sj>1Uy;ds6JOYTBg@np`hw>^u(WT89~4d-o%`9rj(XzTl`&e0vaP$|Ob$-nx$TnolzE9IjLqI(wk1r zV!CZzQC@K4hCl|HJ(qv?317P8QS+ZJA_CNN=^eT4PYniD2D}twoxP>XdFZOUC!^QK z3*b7RHRb}?J+oy-0A7Tvl{4Dvg13OU&(z-|snzHD{D##xP#hTEuXiAnZL)M?K!1cY zRgVuL7rZ7*qCX2$xKY4hbc82YevFwUG4Hl`#gSb=QZ1HoCOYkMI51S+^7}xu7*K)(mm zq(fbUOP|wVu;pRP2(9p$EKkWwhcSp1RJ9>R%k;a_J?CeQx18|%UwQk({u=7*QFybr6YymQ&Uq0HIYiZ30`UuE8TG>?Et!5II4s-!-L>h7xneRXtC*p$f}s) z$F>_L*2a{L{8M<>ykE4hDfhGY%9$I@kGCDM6l*s1#?hs`j5K1%3Zsa-{7@Y{fX$nn zpT87z=qjSdp!wpTFUH*6-9n@J^O>0$kFpe~v2?B~usU6ENczy)`bEr?hK7casLi$| zbAZ6syC^{`T%r=UwKqYVhR^deX6FRy$3Q;O&k8j1*JVyhLg#GKn50&I(2T6MTa18< z0Ka(O_hZ?V&j;|_Uak@RF8nu0p`P9`N5>xia*ep4t|;j$+5=k?ef87BtBtb;7qb1; zZTmD$Y`IM_%_ugr@;hngO3B$;1)3=)rZN>K*z|OF6n3h8uo;OD&5JwFeXbe)jQptb zDZ-UuC})lIvo542ay1C<3v$B4SexF~`Qdc(9C(t=nu82IQI^@lnZu8g&$(479e83%PPmdu=*UPm zsZ#HgbFpMps0+eSIi{DouG`!7Q=?=>z4o2Hzs<^U+Q|aD^xP@fG zitNT)!#*c&fZ7w(`Ew=Ie<`~D=`(4g!6?r+cT{vAc1O#Skk6DF^Cr;Q*;$zaHTRQw z(T-hn2jBELW1lGNET3ov7HOt;+?3)x(OyHI{UdEnP&_ARjqrXpJSk00`DO-MG>!{o zDAO42ZrR!!Z}?);eiLF_{66l*#f$$wjE}f3FpWwU842;g&OWTi49Krtwl`3EL!VDb zuCS!-WA=99<)Nt+x!VZXB@2FZKr>C+ViG_aqSi+U3Pb=a0dYKw0Aun_Y@8dJC?d7B0TYywq8*d9Fk1fc}C4*lMYj_#BaU4%_ zDT0BsJOD}e@iB-p9|k-4*!Ac11o$}+0`7An!`90M+fhBhtVC4h@u z`bd_EjdLuY9=J|~Ls|7gOpZAKp8)v4*1#u5H^-s5P~ZnNxw@((E&cow3SA~3rivd) zN=&HRtW>4Hc3@=FKsRWVcU;;(cMHyuv!o~vR-A)!q`ZVep=eDV#!r{V7uo@r+7cA8 zRgoRNPs!+-Dn<7+Bl=V$Na6nxD?^xiHeGl8mH6pE$%;-MW1AfH}VTQi)lfsqsXCKszWp(d>@{FqB~4XoxY{A z|Cus(WiS&bB+k~P<76|qdiTHWMJ@LXoe*WJ5H4mV8>h0X*V~1YYD(#nb8UVZjvZ9p z*p!SE>I@|!(E0o5q#6R@Nb2Xc`2^k4JtKu&zZGQ0H3jiFpgA4YG*F+RfDb^ElH%#A zL<}8+RQQ7Ec(<$PCr!=j?UFU!gvH| zJVR5-(Y|z<-rn8)mqXd${{X4fDN*3Gg1SGLKbMJ>`J%%$xad8(I?&WvG&0?Y2Z@O4 zgsmQCsLZAy<|m=YP8 z0Ulw~#J6$J2gsRDBoC*QHGoSz*Zh+4jeKMGQwW3nh2yA_A;%>Ca(tVLU(R)vDWzF6Z8DGD4_!@5-T%k@qx1?=6)rKpIrg|cGWs{ zR?Z5h>!@=E9e7i$eDWAbYscI+G8?Ttwp!HI()uN*aW;*gxltx?VrJ_ScH+O={2u`v z6bjMDikaRij<9Ly3P+f)hUSc_rY5UDlHudyXUZ1@e*0vUZ0GNOE*MMp;T}3w+O*jy`R3d1w}FI8 zeWC49$EQ-*!*Mk@E{iED=jgu1znd`9yFuuhxfVwfp>I_`l=+< zy%{5{M2EYPQNQ-*tML8%6omqJW6eFf)n1wzLeBFPv216fshUpZ^`QVi=f7@?ppbR<{zmtqm~*Zi>czK8MJO6QJ0tET3V-h3(C zGVvKlBe78X8t&eKW%T3|0a>Fj=?D`yB;;g!E?2{UaoBgNI$__g(Q~z!T19P8&Fz_< z0I#C@k-2lPeuvbX`b&MK>}tAj%M53wtaqK5=BotV4kXFSv0m51ge-=QL1l0WiZ>@x zND~v@A2~&j*^O__5#O#XexHw2m&LKL>`dh1m@i0gT2b4<#eh>k)25X-OYg73tgHH| zBa&oMmf0?+?t|lVeUzVH6r$~ai&1G)a+v-iX+M|o`LGbp%0bOwbyb`M*3Y)OaAzvB zc?7<(7)owrxxSB4^=5B2-p{w|cNBhxB?{ToSpVQYXfk~XVP~$WK$2o{rtU4YkT;d~ zRvGn8L};`x%b89oNC|?AW$SnZe6q~pZ}+fM125{{-r>4i))VoE4Rs`wUJ$MaY{x8^E3S?tc9T^{-^Mq`Q5%33Ga%w^mHLjOZ*FsZ1YS7UkMBG z`K~xl+~EVr%Mhy0&Wa{{;gxBEL?+gk-wV=EV^N!_&-U6;LEWFlnW8Wc{jF1PsQ&rMa}OTVrbEtZ=sAfF~LIt5}g-faB8r zH9=GM+tt5CgFB|u5mMF>Hd*2qa&ZdqUiN(zy5H*!pJCpOCdsQ^Ly=X;HY7Yr-u&?0 zVSyq1@GUnKq8}gec#hk$Bvh&52fq&%@cG?xU9WhO*{N>NWVH<{8$ZwoigaWaw^B&9 zSP(2VUNfW0Vtx6%b|RcOw4FHx^*h5MxG+W}mZXRcAOr3GejiF?x`~XYCMcAOFsGyN z=GnVyizuh(1pN3$g}P*W|ahuzM1*?)Le>`@1m;A`!FE_0$~yq z9*Zs230nPDjb59mtgZJPtS$d2K*MN4UQv2n^SWzic{GT{L3Oa${hrp?z!wrv2p?)`l=7Qpq6`dwIs z*-p8aWG&i8?BGMt+MnKKSS@5MQYd`d&mM+QBSE5UdNEBPwP}kDMG&cGe6C_7PB+c!?Pbjg& zRG9D_T|5ZUut*{rZT=}(a)5z_yy`F$E=cj6C(=LHAZf5Odj+DY+Iip7dpV5%K7K-l zn{w5P8l6`P8CSAn!TTejR?~)|1Kg{F5kw^E~m9MLxRFI?OeA28b_6l7oiXtb=FJt@wAof@q2A8 zH|Xo?s0CRZW$I~XA1f4=w03NaO418ceoEW7&%w(}N={G3U!N5{C;i!084K7JAp0lR z+?>i(;hk!*o`J7g+G^ua8XNisDq8Zn_5MpViDLrLO`X8OXMrGma*V))O; ztx6|HE;Xl==4j;eWZ%eV9o`-f!Dt36dB*|4M7(YwR`B-mwsCOCD{ak4O?^iZi{{@> zCL4Ep_YfLiTlOFQ1aR*@f!3KIE0uyYChbKVXR67?ub9%&>#y`hjyqp9WY;z>TRAeq zb&W2Ol8-0z$uu4eoHG9nr*IqXv2!cwD|!tz;II-kAgw_%SMh^NY^Lya;Kajpv@jut@u7^ROvs?|DN8yL=CWw7&)l>92-v$ z1Dcf|RiW|Nk9@j$N5tkudE{P6uNZsz`5v`!L%@V0mW}nH+2hU25EWdMtbH|NH01Bp zVfi5_ECvl7oMVDrwQWM2Xw$}L(0Vg>f358rIYZL=3%#_!pK|MRs<=BlyM%-!+mqWv z22H+%vT^-Z)irfB^PMofy~{~5uaIje6!HMPj{97p^b*T#mD9uMO1!kFvhCDYSS<)` zZ-eaMa1(LVRjs+X!DCmlVwE?>Ng`@t%xrCjW*(QXAefuhdi?MW6VqYT{idU&3Ie<~$D zrGeaCh4*2%A;B`mKDqpjd^Z4C5spfaS{@JJU%LKGw&oM%GhTlh-Mz5F1HsQ$FstxL zl3kh8aAo##lu&XX<|0-7(#>naB$N<}yvfv&;nK1fFO}u!s<@3xz2w~!nOk{Mx8G61 z$=wZU(}vWU?8+t?Gu@{8}QiQk$-T0dRTV5=VLA{1*T}R zddAYw+G}m>fR9?<=kK}_bsFW!?yS*a$f9ibF=p&jobo@XtqidfAbsW3PCO7q?&S;> zsk|>5v#B51@EKrpwTlSh7Wn3Q9~=4x#a$WO%~CuR`VcdRuL5e+I(~Ht58Mc)9=oIy zMAX<^<=D?w?&S*yZIW}7h<^+*dCVMe6}ohKya-lcpsLNSsQ>&thfXesE|gei@Vx)FpLxIj zS!4^rx1~330&AX5{+XE>0%6*kv9g8xaQG%I@bhwGZTV~$UQ^#?^C?lSWTg$-GOO4~ zqB!HhC7UQGO@{Z`3mV0@WY_xn8(sK6KOx|m3gWxhr_Ez33+t0@n54km>Er~wK!D3` zNH zXG1g$Yc{Z3qa`hgT{ro(JRGL}({SfP-7b_@@tI`vv{^L=pDpp%;(E&x8)(vg{^AcC zf7^&(l9W#)$8{WmaXSbeP4MqW=P_?t9A|wa-O7`hXOm7|W0Fx3v3VtoK;4s)k_NWV z?|aLiAXyKG)+wo}79Jj>Mlu;4uGx-lfX%=>N3g5OH$TDDS7B3v1KVJd|dq|=jfL%RLyK$7A!SC_$aS@t$Q)lPzK#9P?$*JBH9VEh&Tv%B6^}nLCx@yE} zC0Bby^Nxt9(f6im1j*Z>AKCuZ-@Atx+tfPX4Zrq;yy*K^Iwfvy_aZ|Bce`7fzVK~? zQ`<_1f;{$BEr#O_x&!vrTJtf3UmRxh_o8j~_x66)Hl`R<_K&ZVllh(^0%X^+ z^f>WiZg8rd(YA2eq;&G~?AD7q)UG<6=6Y@vZ~Gk2!Qr&3sZNTV07O)bbGhTI*ATiL zFcJFH?tJWt_Fki$70XLb=H@X_E@#|0wt((^l|UC&pWqIj_)aB)|7u4Rsq=4-D_tcC zjnuoFl0Olev!VsI`DpH)8U`ae0E{UNyVUA+=QQh5Q({Q@Jhl(=|!bs_aumLZA4Dm`gV%$7+G z=~vS?Dw{9C*u1^&RI-#QLHg=a_2z6QmEk$M8#oS0gLg&?1e7_p5YT;#iLN+5X*JQV zP}g2wLa}Gil|J}~U)AwgS?_*&>|InpL=Et8^%efnj) z=nI_PZgDYZAceO^^iT{94b?q-UZV`(*!(2C+vx0(cevOXf7=9^ot^XA9N`_3 zvr$x3%u}Q9*dwT^T4aEpu9QXFakegMwYSf3uN+>sNZcg-%(FyQR-gXh6*yTT5!RMo||K<}9KlvbUJ2%@8 z^A00qcs^DZEeiMEgGg#pXR$h^*qMaotz?X)!eSMu`CZn~L4XVz#Gt`Bkkfi}K8ih2 zB-O{RdiA>P?ie`gko>*AzF4#`e?NqstwMmM${hv!8I$^nAPcQkI=b4;^Q3?yvaL<% zzhG}zaWQY2GE@``*>H~2-rimrC?k`F1Nq3F@nK6=))o}(w9th^$&#RzI+QUhZ6kFD zO_|F1Y5^*MFND$WOH3w)+aoQOJ^sXsg?9LzYF|A08SgX6v%H>}CRv zO~2Aw9dYI)wOz>}<9>rk_q$9Uk>2xj?DpHCb}4Hg0Wy%hS{kbln7-JUA;cz9^`19P zT5Mf5B)w5NvDoFQ2uippUBc3Hj0m{^6}R5{K4WNI@0_MG98EGYu!~Vbt$x2-{$#yT zt9gI1_O#0ssdW63`}*)wA04*BD^5)^?m>{-(<2EGo&SO&z&uj|jFWHQ@-O^w z;IUWMbMo965s6AIlUPiO+gqy1P0lET~I5K6U~i0m!SU z>B$*QTZJ6UyrpXpWAVIhP@2hU^l{SP;4Ex%%tL$wfJ^YGqa&QBa8H z&7Q^ya)jaZDL+U z3_4~b4h751i6%&Jq%b{?CMJIueK!0$Ktf1=J=uRh`QM`Oopm|{8oo&zU0rOAKjED4 z7>F3uDWY2>6-QNO*eC^c;DIeO+d67FN?Glywpdc(0LVaKebKtoPc85GruOE!KxHrKN?1j3}uJT$v=gR39In9#3ux zjqeJH1-v84?$@8!;m2vqHQjy4$mt$AL}ftCmdm0~RI09P8hp539nuCC0LKvT1Rc${ z@Bv_O2<#z5G;=~bx4Cz$3(!+OcQdZ65Q?hOf9-$pG5ReBZv<5~ozElEM>(AwJF2Rw zX%J+MJUn{_E`+mKp3z*MA#tki7MQbXASoNQsTgfn$jxzvAGC2}!JwmAhsrxH) z@`g~7^48mTnr93cJxEBHc&Z)!wbeS1IX)hV-FI>LeqB#|3aS@n8DqPA@;mK~z z1CNP5y}2-k1qXVn*$8IWq==PN0JQ5G8d{#Twff$kDNm`ab*!(GuidR)|1kbh{~@Ao z@w-Eda4W~Zm!bh8c(z5dDmW1v>K1>`TR$WELqQUzi`@ZHm_%;o39T$P7}58dMmst> zk`QEZd+Y!igWIrXDyt*oHDWZCY!m0Zs7L$5U+|dTcl_`ygd&ZD*KUo=Cx~$2&9Q21 zG-Q8W+@6Ca6h5c5yrYAVmOPgyo+2fWACEy+*%Y-LB2i-X112{fl^FRb3e9!}2 z#P%$GN=g7h2|Z2k-q5z+DD(NAvI%$|ckf=D#b@1r`H|A!COJ?!{Kbv4AQzj?IV-|f zXbkX>T0ea7y^#k_0-JqBAMGeI2EHp4PH4P+6^Nv=8;lc3#p>()%9t*a3S;R!e{rv? zT9tGA?aT(3zr)9m(s7mr)>fb3rS+dSOY8eBtG6&va$?c;ZbPs9%g^Vm@<&U55VMMG zqcAYEYE#z@>b|Rxvq{2fxYSLj=J1p)MUL*~_}sq0x8Sg*F`A^gNUj6PiSm|^j{eZp zMgMEMiP;HRE_!a+#?{sqiaa~3_36G+UC{fS3YJpg^9bkbG~yN^9?3@mx{Vw`cTRc6si2bkuTnz?jELXrWt$?{B!)|8n69Ioesv z+Th!IdI0h1IF@Ld)1u{098#yrcQ@;?YOq2Py1p5k7@zDAIB6dNsdU1BX7G)-d+?2^ zGL-&H;{zD%nDCRJe|vi*V%%F$kB7GYQ8^kq9tu>%{1onQK53I@!{Q>)#KHASJb+3E zPVgYkXx>*jL@e;?aH6d|;wPw}?wIa8-YJ1@NtN?n5}$h7 zEVD7i){ZC*Jyl5K_-hUw7Y|RITz&%-K8yN!t3eAaOPi=2hxB;_N${MX)fH2<&YOZe}qW_>3+CgQ3n5yg*HAp zDQ0X;2And$YQ_P6>oDWgo`{}vdHwr05+Dir9*5C>x}T;8`zw08clL02L8$Ccx^HxQ zhr^0ho|lT=zPmO>u#KBytXHN!n+=>(bxU|BZ$BScN#RPG+Ign}_eHn;!M8j3cvx(Z znd7ES%%XZAOydZ#H#a$tBN-NBfgl zzuSD%M6TZU_xlhwR`>%!ZF3ce*2d8>zqT~$m}G^Cm6`JcXIFPO!I9$;z>(t>^1)Qp zy*UE}Ia1QnwvLWFX8;_aQ5EmlrOg;{K3e2n4LEt(se;xnyv|n7G#A*Ic&@ZlT(b^& z{x!6$xWG8RnsKN`g>3;hS5|pz#B*(Hw96A)19c!AmE|8lSGH;uPcR6i-C)fkdzn_6ew7a9u4Nn-3R}tU^1=3 zO~h#Tmr<$#H1RjwZ@U;df*^7ut)eI_02eJmmP1|6b3)Ag{Q1 zXmuh)>^)?030<1vSCbMIF%9lZ*V6JBu&~F8zvp%nlzqVIod;rfaDJhHNy<~=w=e$5Fy`jb|ZCAFx)$d;v3?e9~ zl{4Ybb@h;<&8v8iJ43$;^&e|w^I<1)5*IIrlc&rT7FWkhD`jqtcLvwg)Bt}sV46^K zDXrwJS(L7cPS7}HXk^(mA~NP-4lQA+0ex(Qd?~xlL#!oX)>t1{<@;P6{wZ$1*K{|u z_VryJ7vUStay#5>Vw5v~vExuo;z3W9^lBT?da;T8n`Osv$}^h}+MWoIYXGBr5`x^ ziI!zui*leedOL_&e=#BU2}j=s($}=OM&ZbmZi5Bir+>*1X}y z*#Rb>hxJewXcxR0;rBPbLcP*`1G^W0kB_!T1&;IbD?{LZbE?oz1v2Zokf*bxa7=LI85W}+AN|3TTk5$r%*Yoz{i>w#~kNA z`RUvkB>hlfp(P|{@sh!}Q(TO$8|_lR)y-(C8fTF2sSg@VuiPOw+w2isRONj)Fr-Qx zR9l<>VrIWJ2-W!G{6mMS7wp`4stGIf?=5v3pM3|4fa0u<%q0YA&`|QemE^xSHR>Rt zkuS^TsjXP?D7u^6-+9l8UCLa8|6m&mxZO1D#uMo8pBjR9YfgW&^QAo(Eyn^sMju zC#J))(e#sXiQ>$xvm;IK zY8j;u^=zMhzahgb$E!uqi2xv{QisXswY_gx&No2mN*-e8q{!GSJX zDcuJU~Y0+Z3tuC%eA-0k2U#nz3Nw*PIJ!CJx>rftc)PWEeiWMA=fY<(04`qzLDu?>k7!u9k~awjwl{zRI!ill zowg1L;SX(8vKeG}#El-kLF8z8YDL0onwRAPnPgJ9J%-@neeJY6zoM%~MuRgfU%qj1 z;~@1L{^lhrSS;ig7e@dV!c!&;CRHRc2b%xxVpsz^Uq5g(4I+02bQm0rkkcFAn%dfl zwf~Q9fTL1Z*B_7c^zF4MmX5LUb3vCCvqtr+hL>5LoXx&_lS1w$GA3R{T1v_vV7Kw7{qE=~ zTAIuYS2ph7zH-1Ir?595eK!30xBSB3rtH(j>2efN$mFhb(%j&}5H{U;9o5v(;K%&y z8J?u&VH7(r=&N>$Y)UY5@wwcSg7(AK!7e8^H&~2i3`{j;*RRJHCISm=hlfWuuJ6Et z7}Q=6xB3BqYP!by;#iVkpGeRKjo99{1b+cqRXzZ%BwAp@U#1ATwJI^u>^FZ;8KF)mQI2To&x2tnbHn^|&c!I_~W`4U1Et ziT{)JSRK&I>bK1(c+*Jh1xBk+r(5FP#TzaE?js^&VsKvmdo@u*w{XS~U zrX7*p{=$m5x;ajH`&H9KXF;+t=@>_aExBzn0`%2HmEJFe(DbJy1%OOy45S|2I9<)O z%DRS^m5xN|aV=h4AFgx(KLy)gA5DG+d_D5yvm8tfkhoXvZazRDhF9#!wBKe@O%;h}>snZ$~(T0_Xh}J!mLNs|l zqTKO(6Aac-6t@>RXK3vWj<8Pe7j)t>&M9yz~Ul+q5XR;AbR~@Qs;Ni}sl6^(? zmYCn8L7OvWSoqH_6T%B*BxA5X$yz;5@@y`>PRkULWq3vvo}=+s^jvQ%8DNp;sh8d` zSWYT+ybe>Svg&{QWFWdS12Hv!udXO$v4NO{i;L^jGvM0u?FfDSkiR4R{`SG(@=65`Is}`-zHTE7IxX^;W*DQG_F2s49Tc#Cqnua4JI-L{jhFo|y`k&1kc_+=r+8P_6?bu-@cCk+6Uu=Q(~w1A94Hn% zX|~8gw|vC$(P%@w>!FDVTOni3w`>YIP(?{5ATg+tc2#8Z`#!+h29FTk{`71Y>(_LfnZ~r#?I?;7IQ?!!~}H2eVoVNr1lz4 zDk3}MUUd`H*}%_(t7Kw0ATaE$#E?iqfO-CJGsf-Tsc9Ts*8hH!%|b3dn8FK(r;R#hcmR0s{{60XLnKmD3RWoK9NAo4zWBrL^UPe)IWB4gA6t$ih2 z^!)Cj5Xd4eH8r0L1&XAV9OcmQgotIY;Y+gLf+i!Me-cF$t7_pe095MT<59vWsVD8J zXpwo0VMjdIX2Xg+7(+xvgvb7H4sZPn9t&M7kn^R(q@`sPPZg#>WBwUYx1g>mRe_;r zYZ?~>laRg^zGnkXh)43w=_wl+)h-;4O8&|ePJv~7+=$hXZ+sn+O8D9scsxO?P*heV ziYM82my6%f{6UKAC!b#8kp2Gb{d&A4WaG5gCUAiXIdAY5&-11bd%eV>W&a)wmtBYV zft9Rz4A|M-6Vy>jAPx~pTGY44y`P5xVm$oY3+-| zQQ6u5r}bHG@rr-i0f|!GVLre&ZezdQC$&7_0S-!wI{29l+uUYp(>!(B=5Xv0HHU{H zm+$g7?eVmfcZDrgp<*FV80g4Lrsn5clKStxR}y~Yi;7azpv4C25O(KH)Crp}bxB%W z7Y15$8dJ;5zZuK#aTPVuzjjF(faC35g&5dAfLV87Ko&q?FHcBy7st`RHp*CW5@Li< zgoqUhng z;24YH|192!#tjL69+$^^IjhqOIGfg^Er3PxDHPx6(|-z|(R7@kEB+a-!}HAQE!&YW zAjeY#i|x#u>gM>>53TXSzci?OjXe_?_1g zzp7ZAv}(r36^8=Jz&M z1FGV*X>vI`aWdhNED6C(w7FCb1eDinRXJ?jJQ5ACPzfmaXS$)P)tLqQX)5e=ucrq^ zac9G)x&m|1^k)Eu&&T~Hp)2&4FobAiQJF7d+2!a#ST_}{8wArqwi4GT?uKNKjs94& z5Ms=)Pcm4@UIH)Th^QKSI`lu3Nbb62-4TOKN-!m*8?e-u@<4YfaWUBW_++fDX~F$- zhm2gp|6^x#Z@N7DD@mczv$_0^(A3|5l_d*kHBU26e82wpt!Eb+ygr7X(Fp% znBU#i#N1lDsE*M-luDHvG)he)*WhozUZwumH}w{^HAJcq0fXQ-2v~p$O%sJ#PFO+AD>;@Uv6B2zTx|>S>BM za>R#o?+@kJY0cG+oU|*Y2=yr8%cd!_4Yj^Kb~xx)M{8rzWh~=RVBfaazB=}FFZ?tH za#Y?#^b8twtdwsv_pYX+Eb-tpnpWY-b(ZZ=*h2dq$K&Up>P6DgY<{KoE-pfD%t%#% zhaJrT)!?H*AV_(JPD<8=O#W{%Jd5&;kA^X%uUzWxOTg$@YT-=&)d z26esJN!o=)$oHh*P>cN`&o=p{!e`-wVq2h8giGPDKx5SzU=B zWo2cP%d5jU%7UF`$A+LFoR=21_sq}hq^vLA=mGtdM6N2RL11GAc=Hnr3j+Z5c!L}W zSd_pg@<(QBRf@9cI6dC0d=Y)a^rTxoF+^kC`b-m!^d`Oa=*{bkJ?pHTg1XG2Gu7!F zJ0$h;oScdQeNYkJj_P6TpI(1##X2LN8UZKf@R2PshpjYVl-!? zcXJ0_io!XtRd)f&+QF< zW|!WAR#sNXey86IeABENwIW>QsWCIr+4`l7EAWrpc+O;z6=cy-&;wtDJ`#V z-@HWf*YZu_t?Mvm<+HuXsoweBP+n0PC1+C2&1Q;>#{0XuH&QK!yNo6&_qf;Ni#;ai z?ewW6siCc~Ao?c{PSz>EIoeVP zZFJ8c!Y06(+X;eA3)QGpC2N=&{P&$;TLpF3x@BUU9RDA$=i4HxPC6c2>@%JRvYH3$ zq)nq^8yg!i+WA}UY$F6v}BtRo@Izr{4$f5 zCYF~MC0&&Mh=r}n$^N`7ZFN9C4Zb4kHVKgFzlb%myT-0m@rxo6nf^_7y~&rsDe93=VZYvG-QBOFW9yDsnD#@b-RwbAok#7Ukm71Cs6;2S=J%7vDZv_uX2nYxU*uwfCfFvS~ zN9?3G#S}DIcV3Yb9!6;;8aR6Uzo)R-sD30iZ>~#L(9^>UPvXG&MkhgBj$S zCWq~d=hrAny-PkGu2|1o)%ox6oA!hQ<2UQdRzeHS@rO!--ICG2OV@=`wRBgHIA`WQ zl$pTYL@eO=sd7{WCUCy-Sj_y9iGSys&&oXobd8PGjVGRW4Udfxk%Z>rnU}P8Z_-z= zvm@YsNviKf`38EnSmSsmb<%&5n01#olbC&Y7PViemu+`cvDL(<;7(>K(BMYZHT*`F zIImShiFBNFQy+Wh=9b_gKh=VpBiOP%U1#>AXmzuuOh)E0y}XAeQE5hG@3-7S4mLYZ zn;AqBZos)agxCZXg%m|%b_^rl3w&jdP@b;V?Y%5B!dBsd?duV?Fz`sgecA?j zno_Xnj$IT&bh~FDoa(%9CN^fqobH^G!lDYKP7>JQK=M6Z!vRe|m_DZ>)>GBKUpLUA z4bcjp1r`1=C)~)}FJ@$%lo3%!z{?%oj%GW&{5O($d@leKtgV!t6)u0E0~l5H#h60LMy6C9{@;^ z&pKv));?!989#8o+q=DUcI8b?{k+C=`JQxFm!pgGfA`jD|5H#rs!M07sq0ieH#B+i zuf;TkqwZP-qOOCpv}gm#;P(ICN>SnDgm`5Nd*uKLgvuH!;)krPywX&}l@25De}$8R zNR85D^$Ypu3nK11Z{*4Oao&)gi%Z_RE@IE_dM2E3LfWKn12$d&;k|hNO2Tr-r+r=J)GD&HV2L+SvG!!KX< z&;&a@ECuAN++x)KXdyV? z)n4p}fmOq?--gy%MqeiN;5p9;$p7RH3t7`+9 zzZdN6{r#doVHn~YtJj}%Y+TKX^%P<62ck(Ksp2d94IVca_pKTLE&0B~F$`mNDTk9~ zvnYNoFN*1Wh)vWBMb=c0=TM!YO`d5xzxDNIVQ?G3ERBtg80U{U>#EepJGBM&jYVGz zDjFsTm$dI?N}QFiA8uiyM8OkA?{KzngeUgmj--ykd<&DLibbQ*lIiNJ8lH9#C|PFb zXVoNpxH!QL6VH{S`jU`Jozn63K0xA}Yh;h-+hrdD<&vAq3PTp}jV4A$OoGJbJ58WUs!oXVEQCnkish+oASnVXxV zonHOU$K|{Eb-$d0bCUiIYzJ6q2;X2&`crog4;b~e>YT$WMwBng&O5hX5M0}RmQBvE zZ}Ha>{VW>DAXlg-`zA2~Pt4feoUmzuGNxy6x*-M>SsvGFYHEg{gNFW#8ShoALal~i zav>%x3c`YnlJua83gy5ar0iX7&H@tTI!FII-!w|7d+n3nGtWE-kh{~pk!@x~gr|U2 zezt->fRh}o;7M9hQA~mO`k}gs+)uLIR`~xk+XETPiEIJs3 zD{m(d*@{wPLu3jFaRJhR=0%Rry|gJF(yGH#!@mhYlO9Ow8JRetQD$tdc4ui!MU9ZF zuXAMQE42i6EDv%=V7S~crn!!Rp*AJCo6j)@ePUnRZaW$$3aXTGsS@h5bK~Ht@r*aP zI;d=MchXi~kF-1pm}tMxa*rp2CbHKM5ikK!13;puSF;Hu1$|8670xl8$GcT|7|I;bLFfgbV>=?A`0_0UT?Tl~ZRb^JGCbtD}ct>cq={daKY9+cIJ*Qra zEB5Y#eAx2%hnnw}^oz0h2Zk&iKkuM&d;PvdwlBke)MrLMafI=P1t0<*#)-B_} zZcIo>2uD_OlWl7Fv9qQvT~`3=8$MDPmjX&kn1No6lC8ril3q0qb&St$BQf6y)!jo9 z?G=0UN+{aUIxIA@Yq{N!<+r}_TJ4|yekPDpnz*|sHeP$f1-HI!xjG+6Hh(%`usPcV z9hG$n390X#tZEFs^E3&mN`9XQ{e9r8SMs_x{XVVHZKxB#OE5 z>aglbBfAVa*5A2P9c;rdo7ccf!#+q)PrrMdrx9ow0-GYRfV@ADecHN zuw~wd0B}>~GbKlltmZ8i@li@un&SHM-wkaM2g{7!QMe~lEnw+gW+*y>scbhNhI61C z z`d}FzelJD)2%7%)&ErV1Pj^NCs4Cefs&tCyy$K&?!??YhFkC<-h3BN!yN-6oURx)} zq;Z9;`m0Vo9;tn;J%Aw$o*u+@4$CNLSXk7{w|HE6Unyjr;y-7yy+f^l2QH2&LXu~A z_pmVnYwVZr_3_{Efo5>6R?Z-EJ^RO#0B4=$iY)24DZ3}xuEHbk8)ELc^pbHq4q zpG#+0RE5+VyW_`3+<+aO#n_D*3yq0WP#!d_vOPV&K{@+dU#r&MU$e?O>Qft7l9-ve zfG}=bJx~BN5rjdYOaUO4zUT-1G@DyP2zqcP&~R~aX#{k+TNY86d5AO$?3ht{S7Uw2 zyePlhZ;Xb8iZ#`&Gyh!%x#5$w9SKEcm9bG%Gqa`iKskFT@&Y_dYFG*P9?D}vLgU>P za)04o6tN7wFS)^$ry4Y|lRrum+?X=Rt4^ZL} z8|!5_-kNUP|HT63l*mZFIQ;`%T^7B)EG9KQgbw)44uXC912G9yX=j@zuDgnu8M%ZA zO=3~wIc@EWM3>%aov>R(ZNi*&l@I49FSf&dWXbvO6HL#bc#MK(gyZyn)-P8A!s ztfaUYn3}RI6Qj#ktB%I{TW}?r^%mi$J%yUT;Z;HTo$YB!0kSjUpMMGP@BNT{Q0BV+ zh{d3Y{L?)@t>wI@Ut$QcKHsGX7Mc~lomO2F5n=uBF`IVPK^L3$bMjwHqET6ub&(V9 zQ8I77ZSX*KA&ja)M4Z-N%@VaawJXHt9ufMCD=CA2hC%0*7YlqPU(=##-4b1djdtH3b z&3%d=!VK(}KpLl?VT=^)X+Ru^kMD8$MkXmc)G5`qjjk*lhw;jl2n*S`bxY(Ls_1M_ zeMu$_6GyPZpt|W;b@);6WLk7_anaGyF%nkx!a~46-l*#KIrIt28yHYR%GZw$(ig$P zUS9kLi;J88#>K3xUXB&%nm9R)sC|6*flNl7LsRPYlD>xw^>2(g?&$H)ir+S z--76vGHYucM;hk$Dl-0*!z#A)?TG=?Gd5bsZ$*3BchUT)`sPv^`ZRbpk1 z9$s-qZ#6wbena)bF*d7Z6JI_rf!R!mX_!3*CQjf1ll@@Tq&D%7wtxR<1EFpZA%M$J zu=f{Eh;(vxjw5t;Ze z-R#g&-BQl}`hotDdi|)xLF)AH{LuY=(7sl?AAzd5Qt8f^Q_{;QqlB8XGmPc-*NtL2 zzofgUdP#I(JTOog0-;4tNlBC&x!BNVZ!!DpHw)KYK9x%2R}HW*&i-Ywo{`J+Na z_MGNKKLhz)=IoI1GuijcBgzlS_?j1U>~nMl;+^4WvXwbJ5hNrAMShKffdX#Oog zpMRyf$9T2$9AWON8CUm9$MSBPUE2+9{a#RD1Pl%|7}VYGA<5n_%{~| z$D0BRj~QmX53DY43lavr`sPtMG(Z=iNf6Rn%I#?6c2~C_^iHRD!%6u&|8>#|o)1KD zc^v=H7N+Awofh?3uSuZOj<95aYWZ)Kw8E+mDN%vcU2A@C-kIZZXgS|x{o`@ooI>dEKHM3j!H47-_5EDs z?ZzFdwjGbif9E{L&)dMp1iHKrfFj}|i+o_?=MZI6kXGiK=k7!I69VcIo?|e9{p7em zIjRN(Vhc(X%@_MTq&+x&QCqPyg0ZL3lyWz%YR;0#`aTKsfhI zO}tbd?Eg-EM_FoY;fU9dycjgizE>AeePAaXg(jw$lwmTe{!g%LqGIQ3b`Ex|2C~A7 z*=d#98>dL*@Arab3cr5~$?L(ZzFP~I=bKBOL^CvkPh!Ld9FlM?2RmZ1>D z0eUI}0|TQ(3dXOdX_&HQ{#CuxP4TTiw?5L>-Oi0K{9UHCl~}B}&IZW;CqE%BJbh1l zzuxeNiJBUc!^2o1;@k&~1G_u|+`jUA@YTz-TfUa0!jX}eXXR#omt0lD4T%jk|Mg`b zfS`bhnc2E5x>wAu<%@l6@03w#m@iiB?Ff(C$F%v}Hm^V(Iy}tAT2=3N8hQhj-bmspoPhWx5efO!e^UlKG0Rw=K9SnBG)l2JDP*y&&fH1`Q$EtCe z8NzJX9j9p&G-V2%>{D+4@tgDV z{c+N}Z13poY=5~nE!oQEoo3VG_m<-!?QqiFP!B6>;)V1}ktj3ar5ySA1qJ~e5 zgd#Z4oDUD*s;c&dU2jNcwD+b?gY|2FCdr10n@7APGAB1HR`;yHr+59iU|;Wa-FVdw zIj{S%t-&1OnG8P3&uun5j&6SnR@_XbF%Fy{asIB=44SvPx)HNGtDUiQAA25-$v&oP z1dEJFg)&T0XQ?=_piD!zVB%ZbHoH#80!6?*i>fPM@ zky2LK*k~;wRPDqh_o~ptH(%|K{UzVy2lh~3T3c6ZYH12IA^47}_cm|*7+I0+G5qkp zdsgxx`;0z(_7&~7Cz6+gn4x0K9LJ^O2Wi=newmnd2{P|5+x#90sj2#gmdWpDBQ|e| zfnHOHytz=jZf$)%od>aq#+h<;pWP?uti7W3rQEnG2yc3QtFxiq!>PHWv>QCb6%`e1 z?3`uQ#m(@i5MFO}4fXWMK2Y;nl5Z&MlxZ9sobmZ_*YPN}-i58zC~v_It~4jo;} zT>3~eHUB(#QW^dt;kDiTf>?mf^e-EhU`?lW^|T(^cWMPg_*jm2cwMp++jMd$L@EZ# zB)?Z13_49SInv-)FYaPH?@Wj(D68w}pdbeX1gvfUqfpS64I9s%of!SoefR*8R76kz z=1~M-T?%;qfBuLA#RG|I-*R(1j?r0@zhR`2zM|=~anN8=rgfXAEs2etv|S2vM=#FR zyZzN>_@%mhC>SvQfN&HV?6PxAV9;CnJCKPmbpbx&yfq<4PiSOim6AT6 z^eNk*VkBcn#=|A}X9?>>s87B>5+pj#UK8Aqqbg`WMr0oKt#NHoNOEE zd-^q9Z!{SL-1LS<3FQ)gw9!=K17twUIlIh=#|-XgH;)qe*1RsGhQ!au0Hf+jfAN0$0S6QghBlS z1HNlmcp6G)Yir*dGD~#ihu8@JZ44+u`=wr)sI}12QO;YpjweG*V9nP}z zx$*IyL%V&k%=`7m*G4h*#daRV_dk824W$Y>eb&kMnlAxOLA2j#Fab|H1x4?^m_c_> z??e_-{_o*|fuA4<0N(oP;|Dko{6l|a*75)n@c0SQ@ei2_7QZMc6;8T)S0T6LZ3F0m`=?x!~nXt!meS&0E^kF|VKe$rB>S%K%Fy416%SmeQBOZDeIt zkP?CqKse6C@bG7Cd-|P3`-skMG-i~TesDERgAo1g90UCZlRTg%eA=M)VM4ag#|kZ&&p z5!$=OX4Oa;j#u68i_=wko@JV%c3b_entHN{nOj1@A8L4``X}om)anC{N$P4A*X+Q- z7~h*_;94A!zTx#FXEe%CaEdOTdqqF zgcaeAZ*x4J7`J}h$*H<8#fi0RU5&Y~(EI!Gj6;({BHG$1+Kv5A)7vN@_9-Pu*8|`p z3L%epAs_cWI_bbzfM>MN)A&S;3F~Wq{(T?vX7j@4zy7Sl)D&xv%JGP(?WXU3aipZL zq@`gh)1Xqn)jHv(vU|$BdHiZj&)ht?xA!4D#RI;OE=wf^%K9h}h62wAfl44W0BOI1 zHS3j`xrI6GCM*wbJzF=ZY1AR_DhR>uVMq{QHObF!NI_h2A5bwNlscS73Z|qlPg4UV zLZ9be|4}@Cke(+t zIu>(^=MUD$UR|!fU%!a`g>P4UkM7ETgO`^7p?|MJ`K?30NrDUra=bpq9jjco_?%*1 z?$!w|G`P$xj;QJ^cRmvdu~3%>3L`UiynZG)gNc=2gd@%9WM+DEeY&N4_<_TL1C794 zZT7aD^#((y3=L;W)Q2QBvtO~3UL=K`bu)DVxp)ttKEjf}@(HcPbJR0|7i;6u? ztTi+=AmIg!eoTCP-RI}#9k*}-8*WE3;(cn>N4U%(G;6F}`$bJ~SFmtKc3j1X)2J#z zq|AGzhXEh=dzoMTwbj0h9AK?wV6TrPwx_84D6_IM6#yC_sCOEUs8tz~jjWvRis5|E zx5-v(kLvk0P>vKd;m%X*{6>kLL6=LKHeqSuq6j;L({}TB0|@0;R*ltk)P7XI`%LBE zea^D6@d8MAj-^iZ10iy(uerHFK+mr5v!yO8`hE?``1_5fa~>?>R$ou=qle2l&aR$Z zG*JZWkHAJmYa=LK^x~c$m?oGRg7w45(IA=qhO)6K9&J+kW3BdNX(Nj~ zt<&scN$WCZ`SCmk&z?IDpFmwp2k?tY%P0b_i65Tj<0Wb_ZE$d}ncC!}r{9)}uI8wb zBWIOr-(lSPL`U_jb}}}F*SLv-aJfS4Q7e7H`2Cy^C#(nVx1^%gG_~*QnYeI5q5=oW z3>Yfu@mp38#+xPMjFO%Lnj*~5_V<*l?BKwN^Rx~96aVwa5(#DSZXxo6wClixff8ky zphw;e$T2YN96d#OcX{J}Vi00sPG{Sm-45qyK(RMU}w1|-k zb_S@(`Tj(3@osSaYd4)|?2JMN)2O}S6h(2KCb?tdThxhXa@LidU3A@Ca$&;h?IaT6 z{dFFkpihAu(NcO=X69F*BvDp*!A_V}mLCEyKFoCRFZ?7!d!wmok;I=pWVYRSVeP#6 z_h)~eCEA^GV-4S8s5!*DcVk6LhD!RPIvGXv@z5l4wJc-+iS4TI_2rvMe zFInTD00XVk?imamNN}z{n6B@*oT4vkx+c8CX`NvqmPnZR>0`_0zjY%kFN~3=*Dj?m z{Pe+TBJE1+Ub8e^cr>*k)PN-hZGY=r7(q7*DJX_wudt|M zqWTr^$V5Jfd=iM7@oLzdDv7aBEsRn<$SO&X|MO>X0p~h0jnR8O1fteRHEpl9>vllx z0JMnbUWo1znA)jgIzTunTB5e(i%L2NmB=)~zbuLx{($H@EG!HbB5;FOJ8u!T>i;|( zq{Z~>Sw0}0DQ&&S8Pe<=e12QExASE;__lJi^ z6lec_%KKT6#2FcjWz%$OrQy7}yvBdBaB!jiCFxx&y_iQBofO!LxMUl@D$M>}s;Mb| z5R#Ob2xl}!>}#tpCesIjR8rHW^i@gRmQ7#g&?MJu8%fcSQ!k&Cu>X>{JPXu7qtkYE z!P;^r^-hbJpMPhbm%nam!`YzNt#Yg%<=-k65EuxZI^-!m)@ru(k24B1#;VSNTV-MA zm(9N`;P;9_cRPpK{9{}#3u@;Vikyyw?QaV`BA-yG43$k>wV#pSdzMD}{PFwJehs*h zfNbmu3p+eK>>n5h`#jwpVSKgnTW`(1Qs_WfICY=#FZq0?&c@{3rqP8)NIn4z0vkI= z#yZdag9C(qBYl3JMb+XJR#&~}4?DadQB!m4?99wNjwv0vFCcgXmIX%_r-3)ReZMaG z;0eQmf$0=4|KkdZoldHl-0lKBYi$DA>PgD2t_C}%$Io+-TU8sG3J2&jnzyp z%{|#8oD7JsD4^id^Jou@2{a%0E{iA8=9SEjo+2duwS)PEv((M2 zAkO_Y!#KXf@W@DOc&{~FXQ%&EeG=sPPhSK`1P-vLi1Ph}P(H+E1y{H6ce`fC5eB1c z?K;meQCYvMz~iBriC*cx22nQriar;PBqPXKL}Zq)rd|>Qaqcqf9dF}vF`2#c125ij zt{LJ-$Xi-kWMpJ+*aH#5Ue+qkA5w8sYX)$?EcL9#8Mkp zb?gx3r@YGqLmd6~<}(N=bZ1K+Ir3SRf}mzG`4)m9RIU`2bVL zWbRx!oBGdyV+wAX`^Tc|bDP2OiVxs;ad+OCpPT3HShd$`vJZmYNSn77rut{Gy)5j^ z!8mfeKQ$RkPnxxfYc^;$a-GBjY~HpLbhcF(5O)Np`6nni4oGN=7>KD0vk_)xWg#NC z>fC-C2sqW6lHnl#RHec5J`cGU4rV6;7}@NkqMf~EHV0-W+qR4g)ccN5kw9Q%AaBD6 zVn~!DLB8&MI2Dq1>ObV=8P#a%xW~W#+P>i-R}eBL5@(d1le72Yo@`i{=&yGyZzKIR zS9627J1u&N673IoO-5eXT1JQNC-yG=rQL`QrEoI|8~5ohq!){OLQ0ZVl@sV*c6Smk z4kSp|5j5IQVzHn>kn~&hGqRJUMh`PMK`*71z9lcq7M z2E@2mYH4$X8jnrF?Nj_f=wc z3Fs#&rEQH9bHS`HF8;T|f&iNHzQX>dtX$*WKqeMtC7+|;D5ULm2e2FZ1bvtLK$Fhh|~Zx@mEbnRi-Y4gGHw?J;=gKwZ?sqIEB}JZN|vZxsaZbRgf3M?^nTm5;2$O$CNtv8gAE^ z^&kZ*sY0%9!`8mdQ>@oa!m?Igt$894YX~@`60LFxQNq4>{srV#(&C5g+z9(o;*w8; zPO<4Jn%`x_6LR#2m}y(JMw-04hP3`)H;_FAW_TR}nl47GzHodHnwE*Gn<^pkEnd{< zpO^^F%R`ipWW7AuKt;M;cyclX0};TVP#W@c9LcvEIsJW8=u`Xnkxm{rXo=EutMJ*7dS8tp*N;OyMBH(FACE0sdu zKbNdPt%KUqHt+UV2z`W@g~5FmL=o430;GORDXHQX#Bu!drpBjfuwpP* zkESNpy5mw958#Rti&Z&_flp78D0cfro{v}A2&TV5OPjTE^gO>psHpb_#h{-B4MkXd zCE*E+=Aafj2c4xBZ{}2-Ocq!14td+QfH)1#QeB^CV59U{Zf+qWUg2nh{XhTcP)mVk zRki0{X$snoB`!1*h0YLW<>!P@N`yy#qC%)9Pxl$U5)>m+k#6g_?>z$_E;ry@;NDqv zf#^I$nm(q$DY--hso0nk3MwjyvD?UelIyl>LrmE^!AB}BA@Lk`br@KY5M~tqlPM84 zK$?T$>1SkQWnnQV?6_xID{f(tv_--R${#qF^YS{GkDZdP?tW5k-9x3634ieUP-5F- z;DeXTwagG3OUENah3AC%6g9P>D)hw`JGX0{9b;Zo*EpXc?EnPK=5%DcyNeBGDuP+J zu&5~PT94!YnE@#-93yY*@T?lM!CWUtg_ZWGx=+t>Ja@M>O~o)?eWu0NqZ;o!{EHQp zXTA{huauiI=D)-b9q%(E`RM_CQpvPYHmhtk`qT@5WQoLV+29N{gUbGc2n=Fw>3fq~ zp7w%pIpW5|)E}=TJ$Q%-m?yfMqgo9~a8=nZFMlN9!>5aa*9H(_EY*0mWi#~muc@hn z47RO$f(RDiDdkV@`_TN3&HunA4l$Ec!#{dEXwZ??T9x}p(Vh9^wth;OZjVb-J)Q#) z{PgPDzF8tj!@1F#2@C8wSRgM4uA01q1*y2cz8isEoqz(GL90=wJ}>yI*|JaF`&H-L z!z!C8nZ4F%MUU>Lsc+lI>p@D~nHGXK`7fR5NcYC+;jG&iK)>pC>Lnm{1D59Q-fku~ zK1-MM8fnw*#eJkjYp=k9O#iN)M+qxVSu=gx{uUdEHF)jlV?JIqm-dsR>HQX*qZVy zwpJ}wah-c7^10lK>7BIKH6)dj`?ut6m)*Xk8fhnhUJ-Hz*hfab=XH{}Oc}Az9A951E)r;pIID4k501zzsrd1xgxJE3xv!IcBaWLQ^;k2O#}psFYxvqot#Qc`baOYZ}st? z5JLbJM3V+0UJm$-A}1y^X53b-;^I{i3rq&hJ}e?IORw?FOMVp1m^e*C{ zDkjg-hAPjZ|8A@4-pO5CarAqdOz-`LQ-$4QB~njunl6)WUZOrEOV7^rKl68UlwEDt zcKMJ!;Iefu-Swpl3GXXu57Z!6KYr95as|z{4MDf4(Ow3P$q7@d9X&HU|2^OPN@G>U z7A}nNJ+J4!z+YLd)DoeRGB!V?R%XZejXNT))Cm^UrW*lDN=orE(Yqm75ohTS$RXtz z8mM$`{O?Ho@n=Xrxwz8B5o6wq2;;ZEuvQ~qaV9X4iUuJn@}1kF5ld#AB2IN}@m3!2S&7MeFPOXRFYc74pVlaHOXt?+E(pPPZ*z(MwBLPSzZ5*geg)_gu+=Y-x z*Y6LdAuRnoeohVVmsE^Wd&-T-jJ2wJhD0&r(91ySuxZw)QeOBl{waDC^$7#IJEYW6`}iPs5IA zLsY^56Xr7G*7Y6vtD^3#-Ufb(do!RxVDE!UF`~jECmWEGMfW7WybdmsvDb^B9?KdD zriIAe%X6QLI?v++UFi6GMUFLBXz<+B()^v>yVRdVoR6P0O5Kdml{;@P4aoZhw4QOp zc2HulDtAoACqsiXpRgk!tDKRjU3X%8vgh&LV)|zTCZFVLxV5-7hQs>Q#gC%rReIFY z4tu|bseY;@&udn>f+t&&I>z&ePB$H*lN|^cEcA)=3v5RfaP(L3atLV* zl`jM2J1jU_nmGAjw}piuX=}}<>f53rQgAB;h~9^C6<~i(B2$I*yis;UHl(uh((Lu586 zR$=KqKfh2=j@2&#^+QSlGxQxIW+a%+tRFsv9mUc^->O@J9h_6Vhvq+9B-gA>?%LqmZmAAm{6~Ijf=~>^py+Q-kJk zWyWJ?xv*~AurC!1d=(0hLP|j8@cTCx)M7fejFOPg(sL7 z^pIJx=O*>Jw1a?=C#0m1gYU5L8@=%`i*c`=G6IoWZ~*^(qo~+2BrhmSk8d>F=!MXk z0mOB_p5u1591k`?h#q-JCeR&(`y9NDtR^#yo8u0jGK2(lzt+^WqKx%k zrltP`W`>awl@FULQg{P9ji6&|rY7dT|a(SKlK0hOC{_VItz?JArBfuu6@~#6j#ROvxI@ zSKjcw!=D0ApM3~UBJQc>?P%n89@nC1ns2#@qz$&2qHw<2b8uJJ&2Fxi@RQ)Yrjm8F0yp5JNp!Hw>CK-~bL44SAD6X4NaT z$2d1Xe-Vl`AaTWhOxwloa804Mw$>8258z$|KqRzUbp4O0ys~m|dRi9R30zO9Gidg9 zTQCpcR~g&};7ns|Jf)bufF^bJl(-e+Z9aQcb%&o-p=x&(%2!vEXvH80xx!jb?;|BX zt%73P)FE4qrMqGu`>XfD%<=|`bb&kdN&aWtI+p`3)dN1UCo`@I0iz7HE=O4MR5agt z7BfZOH~;O&7*$mfihfMQai|j3^YZs1dZBJz=Nan`U@J1Tu}e9EZoXt!)4ECTI`>gl zT~wFvzk2VfVB~ESwyYGFSnKX_-MF~>4j~DNfEqSK7Il?i7aMWTr(8}_(HX%R$=$|f zg2CI8Tmq~W@$>)sm=GjjD!9z%-XK<*McF>{! ztQwd&=22TAyuFyK^wuGMg_!fF)$-|&9|cizS(}jimO>f$5X8^Ij41r2s5kOcFn5mc3a=xHt){<=!Q+yYw9S&+~2n7 z+x}|1?Uxf=CwD*G?oDNPtQSaor%?kUsY#or9y%y=hZPpoqxL7;twreG|foN9nf5>H9qH4ruFHf@0Ba@*m-rl&D(sqNvzseAB_fAn-S4Cw zZ&ahA@Ocru+`K~D1owy`+~Z}iemBtAbz$nuJ4Y=E9Y=Po;@d%gEpq0y{(|YcW7(dg zSY1P70Yd5*Bd*sXT!EljTU*mZTxZVCECK?(Y1iv%6Ksb747)=1)B5%{fb$=)hh&N^ z71%Wg3!Eo~se6742Nc%cdRp^7PPbXt=kq_2wC9Znw;JCdJEp`g8^K@w13A(iU#yNO z{^H8;q^vYwUk#6q*j@j+JNa++pv?L$-pM`2ir2Ps@0W(xKY!?W8>CMcdGK!Hy5UwT z^rLtRAPN>Dybmd_S8T3PWQRVrEk5GKrfXOic@Q;O)Rq5j<=ShD<4C-1 zyDhAxjyuttXfIaf~$=rK73p6zQVAGbGt0lLIM&9sKOeV?v>+&m(N3aWWh& z;oI7Wo7+a_)E4n$rtAn7;o6Q>H@LNL+1P&B$rG|+2JQlQuY>+%YGJ`H}3DzSZ^3%_R%ni^TOl zyA(&Bu)>W?xXf*;;bM0KG5%S^&7L4mNGlga>wvm?Z_f_#DkaR_B~SqltvGT5JtVvZh}g=E4lMKxQ`gELKOjN<0cBedIxnt8 z7tTbReG?G4={9fmTPPp&WYO&#CLHdo1!0sKx>+^J_BU~2{54hy~{c@i1Eot-53;|YHYzYQoxUtR#&$# zEKtBk1>Hxmebm;XyudQFuO?I9Q@ymTeOMzyD7IH-po%%oU-zWm?nA|hQM3geSmXxk zPOz-DNKiZ~>Sa7ko`bFWTR~>X1)2MoH%#qGHuasc_g87~Mr2oBqB@wwHO7ynK_{Qd5IPk}>9WP8Y}EWGsOtvo2b2#^F7`H}EK?UHBtO2#F7s*T8D{ z?AmuDyx#dlknXr0=N2?~ln#z7%Ja82of6#m!A=CRCxE&>hsJ}hrpqo6%IwiK?b9LD zxey)08~A#NO~-ZqZd`mk7$`7PQc~bwJ%Huh_IOhrRmiS<=sr?{RsczgHs4|M9VnM8 z*0}X@usQsWM5JMYC+HIXK1LWA?d@@(hzRel?9iql$O;Mz8DLlcUQ`4=Fo-Yu9^S_7 zGVf>N`Nue`==Ems0gvnLu7Xba*e}_#4|)agY~SJ;iJ)8MOSNw4Zy__q_J$>S9h!Gl zH8!cICLUEe@mD#>IcZCbu_5}(;n_!SK`_kdNp|dr=B+5n;?nw1J)RU*Wo2x%$Ih6h zglC?qMnmm(V5@}m3P6{;UYiO=TukR{|8VTltJ^aC6%fub_HgDY&BXT*`&$_-bLCOo z`xW@l3sk)*jOtji z>Q_balo6yMp^T9IjLbHKte7wQ9eqYXF$@33zQ1_hLx?9LmZXJa~!;36uIG6G+H}RgfOFN!WXZc?wAU zpzQ@Ib$OMG-Pz^^gvOK^e89UKR2MNVLPNZgQl+!nqpJHfrY8d(>7cCaa*o%hO_Nbj zor6mO^5qS6g{@%Z497losoadZ<_Fn6=j)#RDotz45Ym>q0 z3z>*W3j#8O1lb0<=)w!ONat!rZ=|QN+JfZVU*zP945dvTCv4z~fO|aBPzg}5z1)=b z1M5in`cI##JU7+ha^##xEw2gGr0+0)iIWpPzP_YzMiaDl1y^mV!V~9z*Uw!|xQhFS zd7ECChUhKN?U*!5*)zs{eNIOI9<`p7*7KLI%llXC2zqdJdGRVik77mfOBK`09$58A zIcHb)i}S17yqVZg4e!eW0RGSJ;xH5@TL%Y1v*)%m+?-xjucWNweY3T{Kc+qSk-vdf z!PYkUSg%K((eE$KU25#)V=?2L@g=xYgdWJTCEYv{NDpMHjI?Td(jUihH*yrJ0?6+3ZwA}`or zhrWHIZ!&q4nrb_eCp8+&)!LbN(_;>1bjds`nh4?$t5nq7ubGIS)*g0*rY`^xNt72} z`tg~pjj|@20B^0Nau{tl8v(s*$k=I z9oB$hy2)ZQYe#{eUF9TM&4stQNw$%&K0KOosHQ%peqVmHm@O#%-yIY@r>rz~m^&hm z?pNOsj3cL4L1>C*w0#m6BF1@AE*pJTFm=QKUvH7-<~Pl;Q^%>3_}{I<$BMh_gGgX0 zjCaS!#zKo7K?}FE+_d>-6-bb*(92lsxH-590Gv|DAw~$qxUE1#2guSoc5P!52iuby;aX>FxKQ=d|!}%FKC%FrGVhXJ5>gPjfyA zm|QctyX%`K09`UGYE&>-f^S{_Zj=a-Nj1dsQdvO7Brc620Dhu z#)U9_E;q2b0jha@{m*085AtzM7k(po5`z@3*D2ZEj~IUPOipUUXrDUxkS;tQhFGiT zLuB|^4ll#U-Ptmhh`7C?Y!mO>wyULf=3k2cveh7tOfrM4UI;hs(+EDg2PlT#){{x& zKX}-$6~DZ;?Wz8iwXDJ)n#PjyU&7=H5Lm!kz^k=MK@NoX(~O1!1SrA=HUf7JYRj5MhIY-{3a_*F0ZS* zv9aMSQ&(CF2@O!IAteOx*F((+1pqkj-dL1%Dj6n018%eJY-w|{PcgIm&`!GR;>?c9 zK0Eb&D_L>50Tb6=d~Mk;Z|VhGk(Ec!l@~Z!j-K{5WQcRU-%;++F8K%wFQk^3loFQIq>@Mjl+-skb_-&gAR3DJ$p?ydVsBxr)#w_H@`|H=cFSLz@>gyR1yieZa9U8?BcX6HF!0Xib%f?zivvJsDILR(n85EG8)6THPt7< zSF=!-hxS4yT&82;ng$nRu=(@uQF?4r?cN+gqC1GX6E04JW20v13)Le~#wGK2!&L#pxGLq!B~_XR@@CIa1`M@2@8gy(bjs?Yb1 zEVRuZcRr#N4~&4tWfrh*YsbWdJ<7`0=U;f(HXp1t!B3)}JXBt${Y0Qe?&+-u6Eqrp zq2->BY7A9Jdhf*V-lIhnEFWK}gZ(J#v$LNy86>!PT z=J6w|O;6WW8%NBrlapl&gpVi~gB7o9lS?{tv}UyD*{v7wFDZrRVmyo4mFg+~fxxqXFX@ zy573I{UW2Z(K53=^v;WnLYBu#^R!IbNv!>n`hp2^e>2oY(+*NAODx9qi(gbQsHCtL zuP4ptkW%1dxW8t`W9r@Co+lomAueuyAAk~yV^E!kfft&&{bs+^+&ARl?5h1hY4feN zscv_!&qDv3g@8uO-sit4hH)Ddg@?dSp*@l8%f8Xg&S!YLU2wG+lyr99^&)R&yvV9A zxF6H)EYyT9^&fAuk1=4%l3)^}>1#(XSM;yDxs03*ANaP}*=RoV##vuq#~my;UNp{B z{mPnuKT3vyus`eJg{Z^c1>+zupo=3A2o}!DH4oPYZx$j?$vN>x?9m~&(?9NBGH+`N zl9G;iMKyBQT(388mj7jHe`t1*FlXs=nYCs~Q{|N;rlVA$SDJB7WR2t=!zS@sAU1j- z^$u6FiyIrzp9xbtLENdzZO_QQj!9v<-FXK9*W-&o^G3bSzM!Y=dPNl`X8rG3Ny)!IXQyaTOQX$|V&Qc2|E-b{AUGk$WVJSlkbnWz=(oyTD|QypNQZmxG2D zrt8CE2dzK@X_%-xg&O*aq2YGQ*sj_Lm0wN9WxYhdMADa`A#5kT@`6vTl$BG1ptyx| z)_J}$5lo%oU2nBNHpnDe^+m96YAK20Rr_e`yQ>``+rU#wOiX0Tr49tIfO<^N_RoE ztxlR{T zJT^PsT~GlQfNha2QF;n~LXWWf&pTZ0f9M}|KRR!fo#HJZldRlyM$Uq9c@N#=dXHy@~<8hS}Ta z5Y^MUtv(TfgNP81<3V9>k_^Fg`h@fPALJotD;JsZV_X07M^VuCMpIT+zHR`I{@$QtsOOY>G+7Zh?dSBBq3O zzvIkI((`Pg4VQe`g%dAcjQM7-PlS65e*qJhxy3P`Zv-WvNJDcBl`qQ7$Q zGs&9yt^ZGM&F8ic;lt=5lK! zXWItcgYZYhR>orFUO6x*`{I z5N@hrc}aiT4D0Eet?KMUpDbAZOB7zxo5aVY|0KP2>MK$$o5)dMQPcjQQgydfA|mx6WOZv&1iSRuTbs(ODQEgJq6 z`MMez8|R8JAm{-rxbg+Vb@`ao`1tG9n~ll{OER)7TnE}&i~?ES2*00#S&G~u6pTfs zFT)+e=uH?uU5w`bu=yFPZmG%r$8t#j*ffhqhDe?+xj!c>GqY)m`&G4un5RuTj3)!z zxv;{Q+sH#dWqdsN5qkfOK7=DoQ=EF#c(JPMOV|45iS~(f?OLAyMz(ZiSj#y`%^qwPwBo^^$?4%BWhX z!dSuDldmUjY|akhoL{$epg;(T4PSkIZi0jV?bc#rV++UkMlwxWy-$%{-hLoOOmvG8 z&VThO6PHFO&dXKmxk%BC`Q5yhh%^mhM=37-DwhryIvGd0Q>SVtdZJrCKp^E8S2cac z0Vf(1`h|`FkNP%V5u|nNu-7M;DD9*TrROXAsSL~8gqkKaO&F|U^VM2n;qSm3xq9Lc zbMBRVI$TO|IOY}ZlaqhmNsj4B*3s2F+Ip05l-aTm9JsN$DJS$YqmPZnhGmH->f!}9 zHH7s>eM-jO-o-P|Z&m2sT;K}cGlA)7SfXtVH(uGR*7%>tEwLZ{H!zbo>sB~b?sR>c z%gD%pD75kKV_S_e0l>3*QU2*u3gE8beWeT_Y}sZ=RTjYjgt(f#JR0DBya(J*b67b( zN((W3jcWew8;F(3acOE;q#~0-;xJv~aatB)&r7boBEn?1Ip#&BiBDyk*iW+U(0p+x zo64;0)hR*h_nJ_iW2VG9FkHhb4?(e!JQ*U8<|g~s1~%-2isyw!Bdq>Ss^eD91G@Q^ zAIr6Wv%LGkA3E`D<2n<98>V*FVXl*3ULFVJ?=VyhVd(yW!uS?aS_P{Esg^t5gm@#Y zVEz4_iio@Y7_%E1JR2Q_zwhAG)dlW>`l7g811XRY#I)s(=JK4C5+BjwuBi%R$;m&u{?p=#27yZmfJe7^6BwjsMSL| zHYc-n48CLaQI}f|wOaYow`O)Yrtkk%y46YZ1Lf)3#Tl_HtDjgGcDhHe!MTJCZK^Us z+}EL~*kUHobiverW4Y^*uQ&+PR?hq!98J}ri!N6G?EU1okw0GEzZ-5YU6q)I*?GIy zS8U=R?woB~C|k>Mdwnwb%Cgg*z4MCW@VPmcCcc_pmp@K}UvVNDn+bbjqGxWoIqe$d z9ZFZ$Dch{9HyiPDF81Jw=riNWsz~m)$*HD@dkjD`pr+gJ18P8+(hd;t_q(A)H0>l0 zyUz+NdEw`WLFg?2_l!2lW2UiR{`Gq3zLWv>vLbH+~!U+1S{8_v)rt*w_ZFNLtOfVAX;f@MzN56@ZRNa{X^#%227lg;GD$j9v0U zQ2ReGHCPX|9=;O5#{{=VB?8C2mS#V0_)6i_myC?^%fWGVX*rIers@qn9K-ZoGko^G zD?OxsKoNNj3*9BpH7O{A`E`Q#>fpq-Zr{hgE9M4@nz8A6!-7Csh{dQdMoq-(Taem8 zH{9<~n{;&N&aUKpn11*8Vo3Pz@Ytc^8)81My#1tEU0Dv9K5H4;HEFc70KSgRMAh8% zV#gGNI1(zVUUpa3IDwD)$1?%@wyR&&%3O@)t+gNAdU17?BOZi+iGdEq6D;9yC(S-} zA0cl1F-?JPw6~k6&I>UzxZ3m?uaZMA0*|A;bky>=Xx0Ob8omvT6B>RPbW2$BBWD%! z91W(Crd{5gzc@}wPt!8hURA{0Wg-f2nQ?BEz;J#r?RZC)sZh_XcMQM++Nr!ge!KjB&d%Eug(U?>}8l>NE*tw52afsPVI(=3C1VUaHSp0~Lp0_i%VVq?N;YP8G(*NGv+c+a@ODg)z^ zU60sJ*%fH1{WdHd9E`c@_hRIPL$1ZMg ziF^2Oo+UYMUu^tTm9uhaj$+AVx#8ox6RN<*v-Kc%EeU{Ibs)qgF!n;4|+=@{tKQtul{B_fg+3AaWhD>PCTIt-iM zFS_u<=%tWYiSI&BG&N=5h>*JI*C2_g1hkH5F1Rrypx_-YGpa)XZy8>3VXrOxkbk`) zLuc)067XwDBD@Tc!Gcte)OK(or;{($Xxf=m*#h ztCZJt^Y$wbt|cyvT1ZL#AJz=PEkQt_&bRG9C@(Gdvg$U-c(Ca`J#$1RlzI~%w1yl? zc__Hj?#uW%u!AZKA^?YA=D zZL)b0;!`sB2H8UGtJ&qBToc1bLyJIo2@+p7sY7yf%gbAj7Xw(*Vsa~-S{rU85Ce$mdRq$l ze0p$nL$DY03Zy=^+Fky)2TcP=5&&eWi01}&$jw>EXvfXj&6`KjxS$a99>!P$BPzJS zDuYix1|DYvZ@oNDXep5IV{BJjXkX2cs_;-YjQln;`HE?I6b!N}=WD+&bp)~xi26z1W_S>Ucyjf%^r6>I-;G5Cyt(+168liXG` ztc~+mUp01B`?l9`3}J~EVtkwj`4Bl-WhVITuYKFh6ngFLt-$dLOj_$_pk`3#CgbnY z9m$_vR6(dHV-lsiHC>7)F^rDlq$io;4{>&EyS=L3=I;OW^fpcRk2jTt_ruq<-sEu% zpvhf?e)E{hNpQISFUpb(lG_jk;%^;i4b>(_f=jy+*DaTS`?vX+$Lcb5d=T!i2)J<7 zdeP7N%9rw=*&P`hD}Ym*L;n!5H&=gL^ghpSb0k+sM?X99e&={RE~1RY7D&4MZZY0Y zlhu|B=+GXAm-pYo(iIhmzhItIW?sVbAGkBt%NrJdrs|vJ7ZzHF360fR0MhObNYX&% zc=%mg<2U@X3WVx9y6apwM_g2>3Uv0>)fx{Z^G1IQv3dRMYg-(2Z)txsovU#aU|zvj zZ|wT%NrN28YKp5Fah66?yUJ;?6^ful0@j}sbpMD1%OO*lQi%(>!I_QZBnD9@a6&)e z6++@=FV7AXhHd&jutnvAwC1d)s4ds{ba5!H-1s*J%H(aQBxp(+fH%iE)|Y`NcA=|h z4O1^R>!smF7LBWDRI!*{QX?6C_X)ZBNz4VUN%phP+#Re&jDnV3brxYF?^bHCJp$zX zZ8Br}m4F~n4l~9_`Rr+ZZ|v)dAH(-R5+}Nw#GnL$YT8;_vfN}QPx`AijT{X{lBP!2 z7mxc8uGjH~2h54eJc3kqOysEJCx)4%CKPMidbaHkIehj-H90V2qk=+)miuli7O)`T zS*G;c;BGZ9o|T{}kOX{RIq|1SVkk*-GB7hPyHh3ZW@DkMA2iP0_gBg2#A18uvpr)+7suNw8Y_tm1Ij8*ffu|mZD2u!m-VT}t0w6rJ3m```s3^) z^v+f`rEV@zc3)+UGLdk%p={!4Ib@l>EySOXuhyp`LPl`t&D&WB+aEU9-YC zXXC(&gZ`r8#6x<-N-97CrBIfDBJb1aPjnfVQmH(?=X4y&0i|oAC|o`KO+i`nH-dvs zOwu(tC{mVHNB2<1NZQkjq76=ucaQWWllyi|Ra@;!P(VA6IWCmy6UelI)|C%HTiI zO@%WHI^&d;LJd4+9U=CP0B`Ve9Q&qCj^AdaNjQvLUmH^RKiQ&aA%O`t=PEotR*-GRMt{T!%k z^%A7bwvU}DKf5=c=r14NkO=O|e{`1B8aR&&(5v;Hiwh++B|Sv@r>GYlZkaK8kzYWM z5_ZeA<2WAGnaFTO_UwNR{BP}%Pq^iP8wq!sz{4&K+`&&NX{%2w6P^WifL$>7YAPfb zf%p&H_DJUpuz)(HvAno>i{-HAxRT*RQh+(Ebt1=i?8< zSE@LtrTC)()HDf+J${X+JNK2kx*XPsW%q4OKO5}*Ce95Vv<;Os8W)jg{kaB1Vw88fxv`a!WDx~{OsUFO z^W3iv-xE{jJI*pHC1u$fE_Mm9tZk+d{>SkTOIp*8ym-^1+n$^Hreiq@gFv}-DC{9- zpKaYdtwth3ew^Pklv2taC87640gEB?PE8V_m+9u(_5@L+?1qifHa0fi*y7^IulgT0 z-?0_qDOce2QkR&eVs+;zQ~^jh?6i=u$FH`UY5!(r`+XinUSFSdTu+r5)hy9UY6ZKK)y#3C@GH_zAa=>je6C+oD^Z5Z9q2+V+<6uM&!46K!7*Vp#vF@vCj) zS1#sk0b}1|ZTJ-7EA-VIu};tgB^j3c(Y{XL8*srBvKD>Z`}OcL5ODWd8oY@a)w zXOXG%752>k6}c_GKYx#oPmlG*XfwYi?rE-MGJfZnwlUoK?F(6P zNSbbx=j`6FrX|{>osaWO#OuUOgbgZH*El%P6qCeOpGeC|6PZvetlh?KO5_Ufr_J3L zf8?!83@$9pf|sSGK=x)I1lVsRgIp0^i^0C^_Qph{WHH zIt!hv{bu$8!`xSIJVce`2ibWKXbi$2p1>OK_qb6N+2i`dg}SfPw@PF+Q?ir$*J`DI zYTu3TB(M)r!jHH$^`TX-FWL5X)BE>4Oz+=5<@nmY6mFasl_mJlSh*qpUUCghkX}*O zmb~t;b~jS-otc?mQ8D5!^8*JJ07`yJcQ?6AXcHAP?#U5hjz&3}wjmbZP{(^wuJojv zF_6d8KRgP*Wf1UU&|A@r)dJ|=^M0GTffs}3c60U5kcfwx8eYlEnNd)cA_Zdqi(D=Q zS|<>yZk^AJ25&gTr->1ypw(ed*}rxUw6G zbzUyGn9zk`(;u*cE+fdzN+j4aZ9j_FUL%xJL~n`RO-r3nSjvXXahUQZjER^ayiy7E zLKBOw;;&87aC$(roV8IXCWmdhsijW}HQJ0@M!`?|sOTu)%{`y3y*>FU{+}^KCns?! zsc9ZJZD;P6Q+#MdRH|K2jL|9(p0;gex{%5Xkt+mV5qlQs+xF z=lvg1Hs-^kdKPgtrk^Mnm1a|vi{99_%N$Ig#bbA8@L+cz`nR3A#eJEHd|Gx)YV_r0 zd{|aQ&<%>@CB@h`+!~aq`en5{p|Oh|Mh~osVlDA);O@ct@Zn%h^qH?Xu>9TKd4em` z&lW?Ll*oZP+>L?v`|2PhFWoFKMpe}Mxi9;@!*x__a3w1;Kn9D??rkWH;M}|gNd4bp z9mit-W-G7A=Neq?hqDC!jniBaAOUfur3lbhj?K(K4$Dfs*uKTyY#p44iy=2b(Go@o z0>k)C`Teu`PFIniDqr zZSz2^KNac)N*qo%E!c|fhRLb@x9BD-OjY1V0>v?w=w|TU z_%sRb%9n;&Q?yMMFRQA)&?(a+*r6G8=*#eV1rq|Wn3DU!Tk={CQUotSwm?cTSz!&w zH*!!B+q1R5U-0o`wu2W*H(QBF5j80b!Mw9td#Qz9yU~7^kg<~uyG4R3`p^UA$z<=E zt2{3ux(F7c z3Rw^nKe-U}0KJ5iY`5iQna7-X;XLM&eEd{Ds#^1NUev5q*=!IIlBD!ul`H7`XIy^R zbl5j~(@kqh7DYRFv8oD9?|0uTM;SdvE;=%Fgw=EB`{*{jju6f?iEd_QrY=rW__1Zq z>+Yntj;{BYNvuKq!H0t{3lxE00h_Ua)1(_{l^{iN_~LjIS{)$Ls(Cgi2=GEMd(8(N zwAm?`%A-C?C$&G9RI3f%U@BjZW&=K@|3B9@aqw6TUA#eE!)(k#(57G7qIps zcM~&XA0PS!6?@h@Fpf|#89zWA7g2YYrmw4O(k>YIzP5K6VX~19D+kws$qUaz~xJFqTIl$T>jish-ZN6o`gxK0IY`0#!4=aq{?sYkxG&=k5R(?_7T3Uc~o1W8z z){c9Ao_p<5lqF^X3wh{UmVvk^OIY8F7dqh&q<`?2FCCnP#GpyM9}H=1@%Rr1#dM0m z%Kei-!&}#O93}peH9yqaNR0d3uS3VB?-nI8c)#J{Eq%!z@SzNwSBUiS6dLnu-4q4{ z0`bHq(}#nEDSg{5uhA3d;;2Vyn!OX4t)LS7Ut+KMzu1tjZak@>_Ml6H1{W%*?Zl7z z9{k%sxaJgE^nD<8{X4<1?kTa*g4aC&Y$MU<*)Gj7NlAo|Ck=R*HPViAs189vq5(g@ z)YY~I0R7`jR+Vo#(uHoK$2FZjoH}%4ly+xL<1qJik{nyR4uV|?DbiVNNMNQ8c*SAd zprxY~Ub^!k>oI+%+;4xFE+G>mu&^bhDw5N{yY*3sZSB824SgLonHmRFOWX|Kid-{=N?!FA^o(b_vf2LvBD$Qg;B*`dWXYl2PHi#7ngl+{j-#m zG3XL>YqKCHwA%w|qDYErO7KpCl+*pk|@joB4dw`FD-CdlXLVE9V{5 z?!L*TX=1hiBOcy@5D>kFHyhJAFhGWWL}@7}3*L;U7qk@tPy`_Yu*A<>&8)^nw0^_w zTG%c=oKcR{M2)wJnDEkwW5ZJCT)O4UboH=6rG;5@SbXM$1N+^mqpepYW%dPX>4vV0 zJ12`JJN{a_KhC7$mNC^Pn$cuF=n<_K6IWmx3N7qOX<|yNJzh;YeU5Jua4)9DpMeA~ zoJj8Oqp9C` zu4!bX48H+y5C|t%x}$T)zFb|NK~0@&`^1m2%vAD8it)GV8=?Wqhj)l7?+A1B@XjdB zg4lWflP9xA&=?_>GaLM)C3JaR|IOf=j8mYd=jCtqZWIHFP ziFLV08r}4*e)isBr+7~%`xz>SBnJAsNy&nhb32XCI7=uTn&0#g-L3F1SP9e}MVK1m zbJ4#vBp#OT9PLp_2V*$^p|YC1(pcYtzbQ}>8YLuK3VTizu{}sIA>IUX1Edodiz}vZ z5G8YQOXg#qFF25mu3q1Y@bDz46!1*J@jrS|AWQ4OgTKyOPkcwF>h?E#FzrIq?Mp8Y zsszm`7wlpoTW6PfMDo=~%F~5`>=Bnt3WZ7q_Y;gY+E`mTjsr|OyQn}G$7#xAEF`^KvV6f0&jx~2@A#|h z(sA`1ih@C?F5tBWPHsc{3CHzt$A!?m*Mu6V&>)!$I!w?^WM`gwIGp3zt4^exYR-Pi zxpc+O@8?n5q32)f?z#rWy!h2xva_QrGsp*Szx(F+ZTnMgqCE#&fugrsoHnm%S<7l6 z8%6n@(9IV6i|dXIhdGk$5%Y01DcyQje)zA6^jwdC2iGt4s%* zeJfRqg{b2i?EVgIn+oHO* zC!b{H=MgHQCq`!R*2fMRZaq0iS%rx_Cz1s-q}FPl_VqjAtAQLS&C4D^pQK{B@d)wJ zfAOo?Iwndyk5I(*wlPsW&}-d=cV=q)_W>R za<;aNB{~C^8S_q|L1dmnj9;ug-|=N7<1w!pzL(P+BGl!o!)0f#cPu$s>;Cn*?VI?- zytmnu_xmq;Iy!%(yiD`Xh4~d}{vvG2zLr^%-LISqxJl(!XexMe7D-8yXLl7v5`5-! zji*;`H2BAhl9$i-ePIr(Z^eK*vUz!@1G8k?psuqDZdUFtTj?Q!SI3cv5cH7;M zEn*$E+|CJS9kR!PEQUZ+mZZ#djPf?2Il25b*&J0`=E0$xz^inL-uXPKRAo(LV--(N zzHnN6+~^qjLZry&X90cvvn6$ix&@(2UyUj-NX#moQ+Xwg>i1}vER4w6hiN=ib1mpI zq2LyP{{bZAAR;r>Z@Rh0n0D{Rflce%w|QB4TShor7bYI{R$Bwi53Pu2-0Hq}H@kP{ zU;0{_;W3VA=U7JG-5dey#gB@FXyOHH(wN;nQw)!bP>?i{i+g;7rK=E#`AlC+#Ax%Z^mBH{w>Rdf@>*yTO;8( zH@+O+W45r#kSv{E6}ijNmEXS8x_c{8{)q^y+udWVY;15_q3#$R-P*!D*bj+LHxEdK z>>SMx4qcDE1+oia`VPVi=h;s&(81FxA$s)a5g_>vfhYQcD`;DVh?w~IMBa4@Y)T!4 zt*tqOdV)!oWX{u7Fx=vW(E)N*HA2^tl*{bP=CR28+@6X}D=JTyu}>Kl4t|ewrl|Qj z&@$jYo2pm^MfB6BPUGyobBYXB9J|NsT{>(%AP>8!mAd4E&KX!jV88l#b^%+ieyXmQ z+6Plo%z?JW3(+AGU7((vwr-|brsFB{uK5P8bc zcfno=7bF(MZlisO$Ev)fgoTp9SEFClVzAt!q8`7`FND%Fn%X}DnB-141R2@c56EM` z0V5hO_|GG|Za!ZdKWbt_Ti))!4YWh3jLC64BKNGj0`PO5`%`>qOfaAi|3Ofk{VMTe z(XbnHan%!1OR|~bjBuP_lNn}sZU)%tm@kv4{u5h@oRZ>Jgy<$<%^B{f!MzRMEz8;6 z3<9zAXK-#h@IU=kc{H6aJk^z%a7@3Oy2~Yd+s(UN+2NtY7t?;TWyzN_l`EXphMcpK z@|yc9MOs|afG+rn5&ApAzm6nc@tB z5^1GL1ZpG020NS{M#iC`A#UgvZdrPnzVGPB%e&gOZ@t*a{x@>)4_8Ctgb1GClzB*Q z(l;$;SqqWJ2%5?8WDVCfYHbw}6RtX8&icdIdJN-w=am@dH*cGpv*6OPslh@-pR8VJ zz&HSLL!Nc!$oyXpNlHEvmKAsS}1wyyCaF9gVWGG0|SoVzMB9 zdR579Y=C6TMvIlOp8-f2(2)3wKr^M=cDgghr53>M`7;k5-;Z3 z5;y146q%MrVpB<~Hiaxodq~Y;pR9s=D{m(MQ@bdi&rZUU>0J{cD7yCyjCU=q>!khq z-UY7yX1KaSB_h?WvO6*Qi}80`+%wIMA-s%bBSv2+jhH-HOxQUT;+HnA|6%21?1_I` z`Zv7vuBZr21|LFK*kK)n^dm#dVHbrB9;>r!ZB0D1qNK!7&(VqJUSE-5dFmEIl2vE# z%a=PE;-_TLYI*d-8<$$Vui1O&r5ru-evMpfy>S15*B28MqM#@3&bztDLly3yOH}+q zw8r&K^3sxBFp^B{Orr0MPteyC`yCg$^IjgH$sk?<=3oP*x*x$Y1pOK?w@t%ZFiVL3 zR9fRc!Nja_2nYu7)M*(R4FJOs?)adlN!L?TAd={~qe#f=c%9FN7=l_OmbQ~a|-QmWA62blC(8v`6fcZ%)p8@Ipa&ijl?0Jd@5JJ*I+ zi7k~LlubYcL1yO?#=KT8BKhjqIQ@FQd*R3VJr0buK%&zJ^%jdyO^v-I203y$>Nhtp zvTkE;d;QIwnVE^k={_I3{Y{}XNk{kO)#&CWu_jThm#NU5DJo<3QI#ogfM%QD{4ie! zc)MEABh&)+LdPu6W+4z=#@vOuaUug=7N=Iu*2db*pblElycY8}GcJOoEXK5z759UwWuDN71-4kkv zcrKADkF-MqoVC0tayE+`90s{B(}7uc$aS;cu@-Coj~+Nx$eA?*_$A9BJUQT?CEbFy zuSEMjJbCrY{i7E73Y@-&M0iyhxRq5~iw38c8VrPB?l^854T|5`uv2j50S`MgfVO}A zva)-gwvk2xGp8}{T)3$L*|Vg)B)_>hYN5ra*6-L(oEi_#n@M4k;O&qq7vbPcNxLBZ?NA0T(}mWJ*(knZ?cL*!%Gl{d&}PPUhv|C z;DI7NO+)QcO_J~9IJy1(_uGy(0xm~gSG`J~{ zey%X-&T&F^`>^J;DTivZFxmAwSt1{oeM7pv#PY$XORbp$1In`U@}PPF{kk7;4uR|G zK3(!`uAXj?_y3&V|0HQ_ZEbfK+p=Lj0Ok}{q9HIVNiQO5R3?SBb$@(v$jE+>s*Hl3 z#FC|s2!GfybcOO+{0U)%bJPHV6c$Q>!q6`Re(bIzt{P>Nto=symO7cw9vjWo_?UOs z$koYh`WqwtqTP*sYyyPV)0%)1_a3zLWo7T$E8^vN`;mT-)$#_|_Y6&2V_#(MzI+|H zod3jeQ@KoC5+Ts?9*XPu8qIBR@5!c@V(vH423oV%$IW{16?~cYhUIeV3A!8);-jMp|Ks}P& zz3d0dgeNB_fK9edU2&F9-HAIHJesXT6^%4VEox6QH6vtC?j=fMpp7Y5MYE}IYu(_(6HMl z#pa6a{ptQY!Fi*%-PCvEPkut#0mBzB-SzWoYh-YHWdVdbhM(ukT2}90r0*o^xKRy? z46#Sk{bgzSMl$M5bX=o!QK8=+B$ck@@yJ77^K`43T3`3%g$9l=3bw9p3rbk0e%1W) z@$j5UucKiaXkMAfFsuB3u!+~~o`0VvzgxR59B=uh$*Uy#_wTzlGYYg%WZgAIJjcl% zb*B@^<2BO>JNBvD6%-q~Df-}2gg^1sR4SeT>|<5XjvjU6O)!!Cik1eRWF=`r?<3wf z@9Z0+adrg9X1^(GY7#)h;eQc=2!ZPPyc4)X!hJdy5*Ppzjx9-#lvsI-8fhR$gyJ9>FXMCcq*85<+sjWNPmnE_b~^3d_LeTYC@|1lLETSQMIH zPoI%%k*K{{m-|OIpDxR;LKkPudC2m;d?Of+aFk%F1gRrTyuG>JtU4#nK*^-v!lNCB zC=jS>!waqlegMfa=UoihJGi)jD;!3YfMbyE^tumn8ql3XZ_EDX`pRxdoyq#X+yG|y zIjjR_`x=8Qn~n2BHoJcF!4EGBdhf5QkE>Rxm|c`m2|2C(o~EllHm?mMiwfJ1zj2c< z6_$E9bYn(mE}_u3RG1z+SL3a4{Mu1aJa%elwHji8zfuW}`E8W_*x)kSUn=Mho}mcX zZ1RL!8zn6^xZE}8-SqEOXOoUMz?q4T^2Wngn-B>& z6)!E-($rLNR3hFQo0{sqz#>&F(&b0xkEP}H5<7nELrP1zfoU3=a=S(Z$J^8%+EBjY z>d(9dkg-K)L8rB4OI2Y7PhOtkQA(d06lmY}=RAFThiGl8$H%E`>Jx4S1UyFp#eRLPRY7{C+_$9IS&{Mf)Xl;#QWyX-xr1=Y+kJSB- zY&Zc6EHON+CRfNaJ3EU!Cy-cK=yuP$b>p=D9r(y%76~23=(rjMWf%5d1+>>ksZ&SQ zJQvMV^C8ShN_v$>&yXxb~R@DYKyh_uPQ zSKXy$U2wL+nNG*V*{(8D)|WUkJ|35O?Z*RuVef6CkH-47j>k+0S$Wu8$Kgs1WB8g| zTHIu7)793<7L%`ddjb2W^|1;XAvZ(kv6d^2|8mGG5Wh|o2|?yy(&`oS?VDEcaYJyj z4O_p7O?<;*Fw}EDNyV@JOzciqzknWi$j!k`F3hwbcdskkwY?we`NqxKJjP5_(c2$s zcL`BD<7j9mOUJ_eTV0DDx>bsky@$Q$j{Qebk&_4V2P+zjbYRs^T8ZGc6s8inpY zCFL6QL7*E+5ZCjeq`au4Uqi9u|Zz3fv?RVcJJohOoAIO_c*!m3y${(qz5TnYs7O8=$?#LxE-{U3=mh`LsxU>Q0&(B}H>-qWl z&J>0&(YlPTE*R@4k4tVTNPp*k1<~38zC0T&QxsjBCmtmqW1)Q3tNTRTd}lC;VdaF) zS1zVMMhTblUnqR=+1oRQL_JQKE_dw)S5Ue#Btte{T8gsH<9>eB`S`_Fk1*b%pOE>L zg2u%6?@^=Xa=P9ENvR#yK2|BIDM)1f^m*fU3|-8ZV(W-iOF@@uMQ!VQU~>dR=uUSD(yB;6~n=!AT;8y@I zOt%M#jY{2!!|{#mO#x7m4}Js2B28{9C`hGauFv91buabm>748Py7D+U_JO6iJKvBn za134kM7)1%oUM`jExoIBgfRLHLq*~$3aO}C&#o_1Qd011XAhCF$ptJwPcDEg1Z>7b zc<`dZ3e6R@L6^?~`GcCX>*U#uBUA+=d8quU6M8Kl2bsC*wSVV2QJ@jcL+mNEzJxzQDXZQ=-7*r4Tmdgi^)7GN+2 z_ZkyDwhGL-$VP_B=Nm?qOBZAXkvr!K=6ar$oBJ;+)Qr|9sMoKDJVG@`>Og5>3+*J0 zA}v?4D4rw7TM8da{Y^Ae<`|Wp4r2H$^nJTJG`i(@yfLh!qeE*D%oSC^$16S*aCvr| zY@cWAU~?yL$_cUSJYHwnh+dcbqcHnq=hf}nPV{AWe3x4Yx?d_abuJuu&KK2@%i`zCDk>n@SOr=yrG)=?%ghQ!#^#KK z$NLdR?9qc)H$6-ylE1u~lEo4gxy8f=p|-pD$v28DPZp)zEDQ^JQUhJimZ0Umfi#lT z)uqC4Ol*5 zL9y^9q%U8V(qa;#4bdHI`oehISDbnhDN@+9e(I3~xIc()yH4?03dytJeyN|xk<|Ai ziL>#K-02WsC@bnfXf#g599jf9Wm6+*Cf$v2YB%F+{6ukHAjcpbb15H>SXcet+@Y^HrRejQ_8~{?i8FmkRF09e)TEb9sbrxXJ;Cf4Z`n5` z)?JqCgFgZ@${v!FF8ABgi_=Kh9zINzpvI*Uk)_2q7=LGo%YEbvIK>ewGIS(pC08B7 z8ss7F9*Js&=79L|5Z~^66W`9_$k346(VCK%+9N{wVvf<$zL$ zsSCU6Dl+&EfHjYS6;Yda#jeJ|!DNt?yAIkbq@auvH(C8XGGnD_Jk+8T%ZCRo2FjkB(u z#G{GJ3v=+ye^4ZcLrCAVgx4tFnPt-Rr&{2vXu%VM_ zOMeTEmTAO`(7SCzi;;YvIzvgLmTe-UB5SWia2cN4plmmy;EA5zV;_x#)dPAZLdhNt zcIwR#n0^1A9~|Z35npkxxIo{s`p`V~r7)sHo>yWR_;EI5>9pKaePDP-L_`KPV_%B`acNL`r#(nbh#k zh*>jds(SqXDUT$l>br97=vCTX&DK%=+JaP)bqTbfj9txk-tQi>m+7@+Ovy_BkEF8< zsA^lguth4|IXK@nr$_cx_=x1a;IXc`(3Ar-Be|$B?Pp<9t8%RsrgVP{DI*S zOtk=IZmND~e0-cNOagXVb8~ZW1wx%MS#FGu?E7Kf;KaZ6@ZObLfZMh_Lq#;IA+J zn(%{=Ub4?yy@45KLvp>3W!SHdo`*kq(-r2?5I9aaD#Wrl(kp+~B3D@hb#AK;7_BG;4D)ld&TKT?hpGP)1 zjt=wa9|9OI*6G8HV{@V*xDg#7y}Ytdo(My2y;{8#a)n@f#hxw}V?jK$tRo*>HTjJZ z=Q@lpeop-45`5C7#5eaHYK`t$wySbzdIwY*-e+f9=Dw+e|2cnR5`GBhndP_ zb7_Kh#lTb7GO=H9s=(yh(sX2gZjP++_%a^+an_ouudDpRt1A)ho(L0s&gv5$2>eC`PSa{IR2+~ zF3-)#*sg)m^S06$U}!91MovshIyOEY+Px$}47*Hz!Y2gis?~?0-$BZX9jc)$Bf?p%kyqcDX!8~c_E{=7u%?3$oao^2s%Jc`VE++r z=XDFi$3%iFMVy$)Ok27-q!nhyAejkONM=LZ@ZEazTRmy;D_fT=+nP^k^?l9CQ<7A> zosZMLyE7A3UtrKs01S&6hsG!%ElKv5Jp`eoEY$BNFg76Q`1q;r18fUmS+u9yLa*?; zCy`%E;eT+76t~n2zS%bDV&Q!Trw|N-5nLfuo=g-`K>QI0sSe;S5|R>CU%Zf1a_5E1 zhJcVzC~za!CT|c^H1wLgXn8Dt_}sBltU0^8``$$3uFG=IEf{|Vms-y@d2$R3pE3$L zHpPl__T=q2j203jRjrl`ww!_^m`xBMP-o}rCkk?Mpof9q#M;Wr2wGg_LV?@woB$aE zty(49p0SVgMX+&%%LKcUI(Qzxn>eSYr6IO^U_^icl0TI~D(MyzYPQ{@%Y&QLTX7-M zn{&zF$s<;V+IJovy^s3eSj~@3n>X{vR7RdIPI(EpLoen^?O$5pZrBfKC#0*Um+N4FjhyGT#S%a=`iK)d!8@m%k29;TK3Q zRA6g+wJfAH#Ak~W;qm_6>1Sq32ZJ*g*Otn2m*DRQDSZuoQM3ORX9F6uG;#jZ&rPjF z!>MH3y(SEP)i0aWRM|xvxG)R@f_T@Een07AasUx7Cbl@q0eyIMR_ral5A2!JS`0aF zT{8RAT&*g6g+{~WE$HRqwceCQU<4b;D>Q=#aPbfeB7maXb7hD@eFyH{)WC&Z0!B*N zI_ts25FB>wa<(_o0|nT9*kADy-_GtXTujX_RH@*?7!si<3fDQ(+M>R6tR3gt=)9a; zu%O;TRqB2dp&?d>}TFL8vw{omW^a-B>Ne(nyLl{ zLrITxwHiGh!6m(%lxZ@WA!*Sx{rtfvKknp;J*w;3{Y zU`0a%BRR%cx%;Q5!vRAB|MBc;MLy`)KZDjM7mRuk90Jw^*tA$&Z_0VDtr3dilHK0f zSp^C#^X;2LOgH5AwN`FzC$H47nnYA;<2SkyN8P6yuI`6?SpYf1*9?_1hy-C9{JNXF z6-)k`Z$`gI{Sy~OQcTT{DKkmk*7SEiaHN?(mYv$83o~UEH)xK#NO^%_QBYuQZM}@I zBH9VC#d_x%==&;ypR3-2AxHb}@n9<-dVyk6pBWhqO@2l8YiRagC?WEbbV2VpK!(G5 z0ItXL)2s8WS#Oj+GPptH2nd0F*8gl9aJvZ3x6KZVi$H|cStz!Hw+ttm6 zK{b7XIgNy^GAydQ*A;ha?(-=#F0^kwJK}S#Jy|HVp8ix+BvWeZWR{3xhwW0?+nhgW zAchN_ReF_Y{$}>(4WTb05W`*L1>S5o4YTM=Uqce>uXGodqqh3A3-KKT4v(gD?GH^r;!@j z4esoIsWF*RT_(sqg1yt41%rhb`pogYke>!GiJM@?VFN6F5p-|!u3yZr*jun4?*04_ zs0?UAHDqt~9=7(lVLZ_v)J;vbvb8sd`vt0Le7I~=d2J_~yrIP9g?ScKAC+uN2d9c( z72`e^m3*rH6oQUTC>Yrz^Od^vV{_}s!s!6xHr*Ong3j`lX8n$#9MKFOui@bpkh8R8 z4o>DkR3~&~NERlN=$B9@KLZ1OdZ=^d?_1m1kvg zOp~#D^Dc&@0$CKNGmODlmVK$;nDt zc$qDr&-x9+sQBk|9kr*{-U6bnSw(%Y2LJWF7fGno>}WpqZ>}8p^9NLqkzM~@30Ep! zwOs>983fS62I6!tCSZUeM)(^NBw95r+7ExQ^-#ApG~ZhI>iht(>`0IADqJw?JwegK z9A>CUSv}b`9;k}N zMO5C{Txnc;4Ko{5fB>ND&WKOLDmNOA^@}WZea z5EBDO3uM34o{k${Xb^ND@y~E2LX2gZY+%deGO^SxeQ4m*&A{UT-y(QltN`O#Gal(1 zYfj#}5X06FcEubPFEetfBvo#55We$!?&T~+`sY#8q44Ndgvf|1H$6EbzoHfRWyP=a zP)>Y790;J^5~f-E*&BcUAF$aiul&KW4L^P#*}uX?A;9(v#>2n|MN}X!xa6GWaEo7l z;cCRNw5ao1zYV_#=p#3HZR@}+SLkT<5t2ANIF~55#*SbJ({CEFbwdYrL#>eKhgBrh z<47STuP~_BEly_?zRVjX$z}am;W2$I&RD!U{Kb18=DiCtN*dofWvH9pa&><;fS&Fx z&O;beStI9BIG{urJC&*_(QS z^8X?xkcQ;^U)hx)czByGj%JkYG_ntwkBJ(7k{Oh2_BX%L$M1r;%=)!+`J;)ao4TTl zW_atNY#y)b&yIOb-h+GhFd^T1txOl${dI$yj8syUtzXkXcRk;jFbv=-Fr9}fu4Wzl zY&k{(>28bnm}pnk$yMfa7#N06bj<>vG)E-_9cTXTqjFUHKc~JPN zs4^)~tPS1}2&cKv(YlXU=r;XBzmD(IirswZHDz|IQTJe=*sA|+j#OHw*Moi% zh6~PpLg6`1&^>mGZBVc$WIcT@NdhRf_wr1*Zy3l@!%99l^F2!9l?E9S837k*RE}3O z?Cimj5lQzJY(^>hHIzUi$_ zub*?u0)GaiRgsWN2Z0z5AO5zpWR9&DfZsCU>|*!ew*triG!jTI8M3)St{x!DgB!-g zgr0TIsKQ;JD6)hreeN3nRqY2Rnem%94- z>U*dxhthummB7fx0!9dXK^Xh9QH3LNqO`82VmyOJzP^!g$?;GyK@87svnOPqJ9wnk z3BFHKFk}}HXRB~$7q5|sJ5$MiXQuL@y+0Y`gA++45Y}L1bWJ-+0M<}q=f4OaJb3Uc z>!K>4YaU4d8ymk7t2IADQvOb z!FI1{V;CO`ad!aO=;Vy{@;%I&F@hw7YQ>&2Jf_F9t}(8% zFe`?dGP{Q>9MumS`3$aEkT5|p1%*m33r#`BdGe|4>5jWc3Pd$RlkorA2Ff{3m=sEC zDBb%?ea2;Zs$kAV4l;TcR@P@pgV7zavG>ekg6QyG3f$rL9etQLB=fE=mwWYKgs5_6 zH#Df6Jz}Kysp55_F*=Hu-d-8sX@%)rHy@I>+EuCxipp~ra0(Zv{7sS$qfdb$r`%_6Ji)%Ak<_53vC7=!wqO2A|zy>c5%>-qJnLurQ#)rkd66LAtP=aTny zC*^IbEvNwzqk2@#Q|#lFavKy8-6_cA#4?myO~|^wAL2!i@N6e^FV+88+AHBJ%f7c< zb11T@M&=o>Snuu(?sRZZP;gQQ8-e zTNaP&doHlOvZ?n{5_%7r4T{N?V6UH!dG*-u}p#R3Y zV`{o|lZdPRc_hf$0t+%{9vEr>=GAUFo7>&r zb__@}JgYHW`a0tPK@D8|{ICym)@e=N|EHzwX)y7dA)J8VW+i|%K#q~Vd0)#kf&a=~MmerrOuX6dPJc^w%49+weO&bhy*@!&BbPTu4JuUzWu&bODsB$Z zhTi|IX{KvqKv~OJ%&kt0fp`}XD{fkvDF_Qej=qoN{@9E^G}8v&M;JgP)!tzQ(Tz<0 zG)sIS0_WmB#4}5VXpuvdkqcpKbsv4;O{HsyROcbZh!P=zm!DJ&{=RS zlFd(zM8oWT9wry+z4zmWmSk&NImA73|k#3I@H z5zOIg_8XetUUE=?y1KbmAr60HCC3VYsY3F=OCjIvYau#ogu`g%T0{Fh=(7Q1`DhAqLvAhl!`E*>6)lK>k+AV~wlJdP1b?m{$=85t{x zxgK~@zsEHV-R03an*X~Ee=bS0cRytPRMhm|OC?~0QBzAnoZ}bmU@V)F&DgtlG$Ewi0X#1>jm4W%FpA{6<14cG;A zDY3$LmX@eQeLui~4Feo?$k+}h6zz%Po3~1|A2?o^nNcuQf$iU$-*LA$Ha0*S7#ph^ zO(hTnZ-XcZ^R$=ZQSd3S5{yQ z>-2kB&Q~-b$^Kf9IOA=L;rV9a)1T@uUTBPXm)`mDA-gUPruptDD@_$mzWLeyxR)&j_-M>om9&d-`mPmW<2bE4QZ6_V%+-# z8;6O|J1(1Lp){Z;-I{AoL#F#s!ZWh=ycpw=QPkAY2_Ig|t*e`Kv*jh|!*MQcj5xeo zJgL(h+n0mKC}HMeliHswLq?e;zSRa2z)|wtD zY!>1evx|TY#f_xFfNGUT-|`8Sh3lCGj0fOW0;l2_xb)$oUwZ9#M)kE2Iw+~Vzl7sg zJvYMbwj+(n;ER@2{nYFSh9J+!zvc@x36@R|0PxMU<+l>T8y8$<EQ14Xig@R|m*h`+Ce&F-VJgwuP%Yr^1ZcoCb#I-(uA6boZFNCxGNrOKlFu zQ`9lG*9I1CjnwT_Q9=t0y$Ot?Vti5Ji|b4cS*nf<|=lWq)OFXIKtt ztwtTZ8Ih##g(>~X`I^}925&LKvMvwcESBroJOtRn$#2qDS!gjqV0P7>DdO{<@g1}$ z(KI4`pb$X*J@~5brznn&kJntITT!7VA~maCp1mgzI)N^R?R;5q$c!mv!=QH*B`=c{5XKV)`6&~RM-%AK;^h|ab{XG_)4FxdD{(_U92 z$o$z}wA`-x^3?v9=IHo)$J^v#uZP!`zI8_YL;=?us~)5nCqIe7y9=WEx7#zdu8WIk zq7Xd``uCFoOVJLPLDoTz8Z5S9Dk^yF^WCMB$P`SIkT)+6hAi}p3!a}7qhlx; zDXCC&`P`Q>R*bi^D=Tl8p&~$D%QJLp4MPhDB{ zEog4#lbsE&=D(Cf2CRw?z0r`x#eF{Z#$jcs$ieK^3w_C+z0~R(OmoFwl;3{z2%^so z#|;pvip4<&75NPma!H5;K;tEs=##GR%Z!y<&IUg>51qFrAA_K53e?XOo0Q&=Bd4mt zi|-3rM4V)w{1k*#gfB5*nSc~QZpQjAMziDZW{*8@d@z+^Sv!2S3rG%ZUZu?z_V!!v zf4cj9TRZSGAi^-NXt11k6UPYCue}F&z~Jq9dA-VqflEI{14E*qlIv}00VtsvZYeAt zU=m?M_$UXbeMS#Y2bk-5G(3Ho31;fY$5S7^Z>_!)!whaF*r7*3a?`r7(dR@+hVd13 zocO54UJi{^em<6g@7^P6>HD}CzW7g;pJtdv*e`41h2xE9Zl5v9-Oe>N)!W%+&Qw&> z(0*6C2@(o5LqiogXIwaM$^tGn5d|pHi&8o^-3k~Pwk>N3W0XVsWs5WcQMFT&_bWQr zCIji90{J^~4_f*Mj~;0Mk-oTBju9HzpO~~F>AW6Y?<+odBiuzo8@gFIh5;%Ch_puV zMKX(BdBa&R=PiZ#`uW@J{^Zle=41HH0cVViCc#7omD>QcQF4s88RO+(L#Kq^TlnCs z!<;-MYli0#K~gbL^T7Av;%)sd`s>P=o&oo6aLc0Yo)v)-H{TZMj$W1-D8V~_1l4lLf2W;EiQ4!%L zIF1czRl(N-{@XvZv$xHzsJPX+1nVN_U$X)YuU>)6D5=e`=bxfu>%|j5i6Ty6M0yKs zfR3pTQmTx^cu0;X*!!TQg3y7R4)rS}M>}&0Fxj8T2CQrx+#ai|^ra=@N!da?3o0c1 zBZp0;Q>U4&YCdVUom4A9^tHnoXSNPcb4L8*)7q1KKGyi5N^i-!G+HgB10xtmvP{Ma zcA6P9F$Hr=dv;tdv*jd>h5oHscM6m%pby#D+!)z+;KKUxhb=z7BVE8X){INZ+WKx{ zVoeWC=+qSX{epsPV`1|n`X76~x@WC@SbMiZb#ERa1f>2Vy!yMa7v*?<-*e7A0y8X} zG%)+AH*df8i~c@&_!S@-#-PWBd(iSI8Qe*dhfy4d}cH5hh|VIyz%qFWa-el?3kOc%2MN zg#%S?5`_xIel(^2?GLWO6MDfaXFf;P$`yS-x6}9zLcyMvS93QehmI8wR*G=wDW?m= zvu14Pn~pR|kTO>RTjqkiE7&_Ds>EnXty=%)4li&lAefnGYHpDkFzrB=sCy!pSkym; z#*ini-&3-90Y)6djNEM$Q8`5qVfzSY%7}@(-$ujGpGh)NR>iMPO;oDHFwJ7TgUhHY zx$gxv0EEN3IA{}3q?Yw zkMFenmDVXZWp;>1LxcLc>D9w~XC?zPrYq~2{V3ivU5R>~cv)5Aeks)wJ^V;9JP*`pGN~kNZ}W2#zjI-Zjr&l zG3I($?^|dsN@TU>h50;oQo-o4nMqGgg;2ASnh%9XUiRd=~xC8eH=B3P^p1_#`;wk!HoZ}iAkx?w~~qr<@4Uxuwy)ae^=L}YM>4poqa6iOv zj!ZH%&<$tl>HcpSUFOMOZQt$JvqO7&`7p50_@B^R{v`~EVb1gdj@v_gg7toi zznUInH<}E@l$6{dh2dPJ;bu6!p>x!$iYS(3+&*m1{m0U$29VJQ6~t7dCkH%jh@Ku+ zc)%or^PRau+YmMnnOt)B3XVSLlxrumf$qn77|H&NH zaIinjfeodippuFvDZ_P z#NI{T3U2WTNurVu)CYn#a38}U6%^@aq^!@<<5ovCQ z6$PlyA(|z-G(W6p!zMb5-b zv<%n@@&Oz6oF(L~gyM5qFPqN_F~5yT(8GJ zC=__9?m}vcvcCxk4InWHzMe|+eiG2X%E(zih>D7Wk7g)CY}aPn@Kxyw1xqQ9;4?jo zh%2>4tHSMeEEVaO*6MD_jRdyMPU&fIZVsApb*mTtJihbpJ1vMr#gy{Y#1!Elg@Q51 z;-YDQ=VTd^J&=pr&~NK0H_+{=wWufm#A+5hcXPT{d;8)JikiQY-Q`UVON_U0X3^~a zbk4Qj%@ycQU<=-^7or~-YX6rsMq0pcpV6`Dg2ZwtQzAiFHfMQ5)YUp-w#!l*U4|}E zEhQr(yS_daJYfrahh+gNytXgz$$i|U=%?P*tX-sh@gkwhLWvTPvh?jne^cwY*3iXS z4@n<>m+h?_fV~$ynPAqu17H|x-eyNTeE{AHi`&{3KRbkp3}7UfRWi+#bSd|MeR0g* zb-v6R>qo^@r6O<5PHWY7Sl;)jX6hyiD%PfpoyK$lpCr%ufUMVOW4=eR*tE;H6byNs zPPvMTT-HaKpy-tXmB(A?_o2Ilv(O_R7?+Yk?d=j~s^E~Xaz(KNuw`?07_bo_O8ooE zPr0dwcZAm0j__cbLi^@WN@U-xUIG-55C!%eaGuWXSoSNm&(Dpj%$O%|V76eyc;- zEg*t5l;Wr6;}#X&1ULIG*rWrp)1no{;)QDVjy9k6JyH+u>?(dPJTZS~fQFy!+&Y5j;7r%8yUmdgcF< z?0+ZlfY_u_E2ZyAy0Fht33?#FCXq#y_kTZR5FA6h(MYy7C#Qu%}e<|AmhT&)jd^ z2qafK8-v_LD7%jCVMA~iWYO2oc~CZ#-ieZiBh2EJO?V3M-8VO^tgPsWaE!>Xz&h0g zB}p_%`#A%D!Q>_`-PA`GO=?j10l5(fF;QQ1YeCbCh+bd5;DihnKn21436AXhiBHEB zEqd9rL7WPE9oPVUzxKp#5<#oLBMqIN^U(nL%i5a9@a@By2JKUQJqyB2bTkSC9mF)B zW7pd8(%~t<*Ns7C>%fTE258uC@kL2 z$v-Rz+1jnRtc-7v>_!G|eL|qBRQ;=KIHN*e_Jfz4FVC`hBx0gVdaCEVgk))=Gx&#o znRXLlqO~sA@+uDm^D{Ws&+3n+duB<07=BHF6(O zg6Mydqvrukx8HHtq#gwslU<0LVUC%KqYg>AQU(?*xl$s;ZnR(iwM_Qa%)obu?Lk5fz|y}4I}h*yPn?2)a0o~*umK=~ zF*5k&1JBknL+R(`TcINaWJk-GQWJXVh6xz2duFK&eOJk$ z1O|)6t;`HW3hCHG8x_U=Sl_i)Cflv?Vi!M;tkYS;fC1=hX zG&D9Aeklb2Bd%(k>~|9++$g2IxxKMDY1S4?`+mfc-v`{`zf+An77OTvBT&ID?tQeO z06{yf?CE2TJUkF<<;e+u4vV1i_v@TX#otJeU6*Gcx16ErQK1U|ZVu#0b=|%m>lK7g zI>ap~DBZU9EP=6Gr!!^u_fy@#66(kOV)$z~TL%w72M`OwC>xASLu(m#ZHmGBSE}2DO&(?*KhF-Fb7vAZ_8l0R>S@v>3VFV>T9bf&D$kxmhXXGzM^VwV zvwjf6=Cbz$4574%r50S!;;F+a>{8ghbQ zJ_Ov#q;cglV`0201w9TzZnf@s&F`7ExW8y9p{ktqp0Nip&ky(Y+Z>QvGAw#b)vJi5 z8uvD&L-=Gdc=pxi7x+{e!s+3J11Y5|4Cn9PA8@&XL!0FhZ|4kD>u&Dus+zhHsmf!M zlRea)v#;rJ5PdNHxk|%jk0{HO_%{!k%(MuAs;O$+jp^=y!V_>l*+oTtctS~JO};6C znD>GCP9*gj&?{CIPNJ>aw;w)uAfZYOBm--Ed-r|D;P#L4{8#g5yRg6*m>w@KEH1MI zt1B2C;@@^7)8N7(<%uu)wiGOVTx06$=>ne7;%zElQL#R*o+-i&;%dT~M!;nR7Mx6V z$qPGlP{G5Z9dc)474K6UR)9DJK1?#KXSt^5iz8A70#4*vs9>Wuuct=Ryt@Z>URX+F zv3CiB7*nTN_A%Kbl()jr7oB*=aXj?;niM|Ky-gB7yIwp!ja2HJ6J-Sz6+a%xy=peV zCh%@Hs0vosfJy%9il)J@fqK`Z?EG?m^NPi@sg;_<>$#nRlSy}|<5>HKP<8PKXTZHt z|K)UYOCM!eeI!-$t!cg#f^q{@xjFb~c@)o`@ zs!7J0TXY!DPq$`)2uKZfx^3eg50-~^^d!TzMaOOgL!vQ{(u&yCTEMX5)e&l{$yJ&H0FAzu6V*(lZ*M(9oO^$=!5rTf zRl2f2LInCw5ZAcEC>Z(-NR_Rwtp&ualB#NK{GXjza|E;r${hXTV6z9$dTa}MT|E6( zY=c{A#A7cm=kj>@+%qUCO_QJ5e*~WDpWV$R$E(ZT^_|UJ5UT&(Vnb`qdUL#;TlXpC zf8K(aC9d;t_#BWq4)hq9p%-gR|5v!ayNRsLh#ht(+jm5KfYqB1LQYten^a6P3kD3{ zV4Pc0)PTr1a=3)s;E8=JML(dZlB*-_4S!!aB|$I*4U*MM+(C;_t`xAnfnhZfc1*U9 z#1UHV$jJLU5j>)zJ8$bSC5&LV3GHWv^^!DlrNe&++VCoFC%Z^k!ocS)uOR2yF^QLEu4N_^BcLPqIy~4(N|HZo^2R-+T zeY5<>EXVC$EWOZn)s_{T3iK@ZkJ}O5OIK*JezNM;g7LlQjvbsxI-<_!fu!O&9cybP z;!c2jHkMJw3Y@$u>~h68xS0pIEH z)#-8l;e;=Pko2hZZo}0 z?URR92z7V#BbKs98rPdh7U_=<^a&SxZv5HTr==vWKQ!Ap7dg8s5EK${-bh#q<{^FO zbe!S29|{W1FEd|n;bGPP9Pb3b3Sy~)plT^qVklaGnFO6{Cy(AZ57cyWd1K#mRmXZy z^3&2wzQR-;^n)<>(RTQr#ds0x-TWV0>C-W{;t-M*aB7-?yBhxD&o$ILU|J4bz1JCak2l49a z;05`9!VmA=j~}Yg?+$m}p!{6?rIQHbX%h4FyLe`pwr&ONia>693?1G<-ot%&{}rLQ z!LnzSY_8S0!AYwYMMcG`8iUPYy1%V~RLi&MYB}suR28o#Wwd=nxtGA_l-*5`{*|0Y zf{2I_P2%=rw}InzPN`+yOy2&EurX?|{Ppj^p3&ZZ<*8;eL#BrqXkJ{PfKDNwC^1kf zG=E3eUpe-`_K)D4zP|9)H~gmm`dDGh>1(hXx5T-N=1pFoq>1-_OQ3<+wR)B-!>_eu z(_1iB_WYR8N7*{{s3G6l7NQOW4L$Vg-mdu%tz?>ClOXQgH{&`*p&s#HA5G1_;oUrM zDXB{Q(j=&c>O#&VEe|&wrp8%kv%v_=d;#?JfPYDNw60z~=~tJO$0N~$9l0en{jqdt z>$BJ4cr7j#IzEimifqY%JxJ#*EWAJRtVFvxwd&Q zB}cX%Ac_YQlawmpueGV)RI)K>cX=X(du`e9gD-bS1@vuKSqvN3naQc@52o?#|JL8E zJrzW4*;?bP-{|;QU!PLY@)vWbY3U|KS}H`lslRdikAP;_uwScy>c4b2fmT%-ae2Hhtt!T>TkSS zS(2+6eV7t-DTG9a zX*2ElmfJ^G^^~=AIG@zWEi5hJPNxnyd2^KnOF?qDc^(b6$usaq+Nw$SWAa2~tgiA& zq^z#K5)@Q+T92zQT>eMcc?UPgRn?*O@MWgg)?;MBrms&8F~cpd(R`EG`$hiD2DLvW zf7*{(ymNKtD+-pW3c%Yuah#R}6HL1ik#-XGt+ETpv{hxM_;ewkq_s?+=wm_}y`OKl z<=xc!^%q^b{xH9~`Dj8ezAPlEpR@iE+SYK9HATC4Ajd^tS-I(%N05}1B>gQxu#kt6 z8ZHl<9)tu*z*_>L4@-O9vI*cJh*%fSBVE2MGInvg`e1`e!^4!JQW1gr44G%7% zX*b~s>%EQ%T3m%ddR;erZnD&T82ngSTW2>nXTb9VC9RuXB>Z~{UK!xeeJm&(X`?>| z_gwdHy4&xF%Gm_KqXl!Gk1z}Ym>Cfc#^;jHMkX$C@Hv`k-v{lm0IwV%O~LN_$ZozG zH*3L>LOdzib#+U-i}^l0qp+)imHr=ok4Q;yT3>GvYQ}3k!dKpGFj9-o$PGbx-M2wvFb+ui-kna1Z}29OZI{){-61cPAlxo>zOrHk_GmpsvfcDM)o z8*Ewfnuk&vKn4l}*y@?L(}L*NueD3~81Rb2%>FT;xO)D4j@Me8_e6hv&2l&+mxVYd zub$j(?&mmYwK$rOC`7YRE>5IhHY>P{mOV;_OR>lVg6!suTT6+l^l@Di9GR5ZU2#Ce7>+7tQ`cPnI?`In|9*w*kpdcn>+L^?U2;;Zn=s(S z6`0P-q4%4q-$`mU+uTJ!LLleP{#trdE(y%0#BZLa^Lvk`=+$Ed*Z*n^4Z=)bD&L;q z0XG(KgtRSjUogdBm*wz(lm)%kJP8I8zp*sPce)Ar5|B|8)V_GveMVow$*s9uI&_l$ z*k^dK%ypqrj|i6E0KJ6C1~dZwBY!!|S}z5!&alNe8{>%))D0Y=g8-HXE4ha}HF9p| z<_5zS2#}aiDpzH+uiG@lyypZ*wBayNq-X1(PnH2#TGb!&L`SCm-hHmYhdp{v9STb z{nAo)$j1fAPIrM<#<2n<@vqTcByN``=76$w&;0T~l`C{Gl(R}nbtW19aKRd_iA3)mCeyd3 z@O}1-nkJ?PXf-l$dOx`>9eY>Q6{SDxe6|gXcf0`3w+>1eN~i}9*rh9~(c9D24eybz z>XpZ{P7YyzaH;wMm0AY_1Jnl7scC!I!6cu#8w<_kxKxs5V)g;05@^b-to19kCFoT? z;T<}CxwNfrVb97^Pe8-7j(P;6dEU?RQ`(MFKJxlQO9e7(gp2X_@-;f_^x$<b{R%!2dku3n`#ezp#8Pt31UsM@|RbuU56hG4vN*A{qtVx7q5 zIDxe4-Xbb0dQ%*>GGLp8hZG`1)GhqaGCUD?e4P2mdT1diY;6VnHy{;Q9Yiw_oRa+< zM<2CL`={VwfIR$}6#TspMzSX_9U^8N`KgWAl_KbHmJ1!t$RA@}_ZJ+_%!B1|*tAZQ zC~e$07A*k=XvpBxM2H^gtzNN#c}#8wKX0miMa5lb;yHe0R+(}=oNX!A9A?yi%ue#a z58NL+O@slD)aTOAi;KTHl%oxIQX%?7!08VWfREked+@&xvtE;qj>4Uqb3N5M_3pAd zwbk4?Z_;r};K1vn*cJQ1vpp))6r%LGNN@$n&#s%%cFB9i#xa-@J;{ueETfI@u`70%HXa_iyIN@6mS~wkQ{ng7%o0p%Tddk_uiY{4iUS5nYrFl#NP`}yP zHsEh{{`te-=rG%RaXi;O&1?JIR}?h5AhS1ZVGgIK(ataV6apvYof4M5>tE?=&nstz zIrxnFwz(b?1RK${t&bJJ=pYZ+l0Qsh;@)8(#+TEzthGE%gZA-v9XkXlpQ|h4bsH{al}B%ZZf7?zEJ>p9tW- zlrsc7A@86Kn1-+yg#{G$`DB}wher}@MF6dsB3tg)eG^o)uslWWuX+neF%Nd%aHdH4^wy+%DR^(>2QL?!6#eRniXjN zT?^U*&=NzC0m37PvT8|#7_?@vtpwv4l&875xq38Yi=c-$J;+xIVS8EF^eG{}K!qEC z(sIrqZsvs%t`i(2V>?e(-#==eP^%A_GXCx{HDYp`pyRQso8x{Mcaoy`3OogKQ*z*~ zg9UgrmIaJ=5pWWzfqx223`e*&+!ezydNHJvJXJ+oglnrtvHn3g8q5;`Objb}D@R8@ zb#y&bEp-j<54BC{qdD|~(X_)e+jt+2yEb%OwW_H`%G2FhA|Ce{3$3B+g*H7nWJTYV zoQ} zm<($v&H?8InJ0pB2uMs}hnu)0cfo`M5QRU8vWw63&JxsBaM}|7S>I(^B&@rpdXL%K zSfV7f(C6{%*t7Qu#p9V`7`T&zG&C{Rl`~?T;&8&z$o&SZpzzr&#Mt^wr1bB20NV3b zUgyQnt-a!6!9usb3OooffCdQp04~?XE(!pZc@Up<9s&tOV6(5hy{MtlX^Ez$q#@w5 zGt1SeABt)BPt8^}J8t;=tlc==?&$OL_to|UHe}Kho2xWN2d^29YjlkT1`nMv2s)sa zC~UnVODan!-5iJM#?H;!arX*gpeqd)|A>yrMN!60$SIvCvZ$!ATX&9z!0F5VWYuZ$Qv#0|}-{ma z+&3wy>GZ^Si0=WWpK*+_y=Il8lVuv-_Sv%3FEki3hCXgWa~=ZvT4aMjNAwXiRd5(S zZKwNDFMweiU-8U~d!47kD;?e|?Ab%eAl80@1HL?%(ZGJpy{2YBDp!v`AoIp1iuQmx=n+zG&iGxj-NlFUD-E>+^T_8+T_VoCD@bAyg<}-C(UxUsEQ7iMdlmnA< z76${d&BhVh%KyBzZ`Dea#MfHb#6$4_{S=)3@OpUv%1Z`fj)nhr{gy|)bdPQ+*8(O5 zwV2C4R~8E`!)gWwN$Pm@B*tH|*o@2q*vmAtt4rPnW2>NB;2**E1-X#Fe}q{*kO^U^ zhghXUlMPIKO|DDD_R9YY)R(sB| zGL^tua?Y=nJA3ncG1`GcxLE7b+4=S5A+!Fxjk~r4Uks|Slr+3Oulz6nIbJ30%p1su zN2J_%qpFdJh?c>DB~ZpEEIbg)Aj9vn4B(2~&4yfw>yXRGBuL6cOhEsZ9+LfxAj=ns ze=h64rJ4*=r zLlqdC!6IY^)eS|vmA!R#MQL>5x^*6t@JC- z>^%^`H`uWp65(finWVF$#jzG0mFs*y)MerquSO%kn?*TO<9t1%7(W6NGw&| zIo;9ee+Ez2n=s?Z00P}B2zS*r*LJ8qz9=?}CJ={{#xcOAE!LQfJIweGSfu8k{9ivbfmDuwQ#lzEthUCK(n0$C!*%fHx_mhnXgj|D5)U|vrpZIt)Xis{s* zo_;xxBrZnB(TofWoEcUPJLNtoo7peRRgHt9b4<0fS@0CWntc`c1<23MA0ZpdK7q95 zmG$8O8f{f@?Sbtb98q2%B44j+DuR*=)~vAp@7lX0r=Z9gaCzI}yrv9Ol#P=EvJdlu z24x)hkrA37r#N@>R?8ne2?m4=tnSS~vRVE0>nLg=rgZbW>ErX)*I*&2sH6hO7II2z zsY=0NIA_7&uc5KNvGYWC_t`!8_7ov82L2dmr4acz_I0?|o?C`iM#sdAEi533Ojgzo z78ecfECw9FCWNAkTR@=q&*TSm{so^aKSXnMO`h`O)U8`VD^zL2#tUp~la>SC@wx?% znV4;rs;}3PZpzm%yddasYEZ5+5yGSP+9xZ5`Rv%Ud5rOx#oZ5D>!3%J0A7 zHh;W=B~kxaKJ;2#<3OF7ky)z;_zL07gRU4R*iic+PW-L8#$=eyAab5=p^c7fGTxb{ z01T;^Uf}Rm^a&V%Rc3EX`4gPx)aV+RxOyVU?HfC}a98f`c~JnOwyT@j>-Rf9fLLEe z+s{m^5)W50h>6;CSsD2HeF=;ecNj4Nu_Lo``r_7<=tPNiZb?aGjuAkJzV*g4dtY{v zBE!bXa9?~Js^WRV z2R^XxQ$xx}t!M1mH>sQkZu2TF{dz-d0o(^@n!x6Xk5k_-cRc!&y%O3cjM5@3e)@83U|7Db0S`q~W) zm_|w$BJ+&^P)m>nrYfte>nebP5H{-C+P#a5bl?iPBJ|m%rbT%hdI#)g2sN9G2;l@` z_}nUClLpkJm3+0tRLygo4S5NoL;h{vS)<9ggMy{@pM#LdYgEB4j2cBI~yI-g}nJ?2vry z>`j>=dvB7xlI(=+y=UY(ukY{qujA-5+_(4jzRvSCGw?<15|eb({|c=LK+7klGQn=% z;Is)JQLs2%(@QF{I5-7`EV7d?$&NfaRrhE?7-jk(av|yPGv1#yw$+~`0`5DDxYx2` zozPr(iY|Vsq3mtGtclzEBz-v2dDzM}-HGbI^CGrrEIX_N-q&Fm^tWXx63J2)zXf&G z{T*yL`;pL$M2sN`abQgF{(C$;IoX56m~K^1!?y&YXIMYGXCXRl0#>cyw;L@l{FhP)Kv8F$gzJ~#aX$V26e z!>-iTr&eW0Rni?!_!}nK=V@#>a&m8KSJIpExu=e}*8UEdhLu12-gA+)zi*drnlF<6H&=0MnfZ&fcx6S_%gqO$R>JL)4>E9#u^# zrjNBAP0Gh14nk2z&SvkD*KLH4cH5EWy510Mg^Xviv;^JxH&ZsM`j$LnZ3#zjbl2Td zzDw$)9Y5&_`KX>JGhg)T2peV;0FQu+0U|YC7neZ-AC$bC0hRr~kQ+_S1!qAB>O(}F z-^ZnB$;2^WFKDUO6HD**M9)y)&iT$>E(6xA>cM6 zMr~jT$EcVL8?b2KNx_a**ZT!zrvKXH0 zP*RRRP|?W7Y6?FLXz7qnzgLF$fXl?i!&e14z{nD?bFbGAS?d3ubEe2?^^=52dMD#2 zMSo6bm*ZvmtTAz4ji*oC1e@4=kU6B9c};~q1~u^@?JH4*aNgu0ohqfA_7R@S^V8GQ zH$R>qHhbph7knzp32*x(+I*P90qP(`83P8|Okh`_o(G9C*xrV4!v8>?rJ}7J%z(Ps zPiXnJum`yQ>c$4BZ?DG;cN;-DCk=lq4oB0wN4HCt(ql&M$5>pG60>PWNSBoZ#%Bo@ zUXNnxt3jI&TiEHkW=k*h)VsTGO?4n4deMxsr|`nQ-3kRRT1_60;cOO&es;8PGT?we z+MJ$O-H?)@Y+^u#-jC{T6TkoZY`k=P1r>dm0bxisuYIbx*gh$(VqOim-U$}}Q_dU` zD4F&8#rkq#)}$FXh&dt|)+TFT%i9>YR6o72y%|>g*fiFAK5hx^?95$S(9f`WpN73? zfJ(@VjJ#AQ2K9?313!%!Nm77$h%}Vs@drbtx5_0e|8)|X36?hOZ_q7%-ZCuw%ROyr z?bm6?SZ30-PZ z(Abgv<)lmwk9We4DfU}8PJVko!P(eAT?@FpqylO((J_j$;tC*L;_ z_B!Pp)(U%$Ei`Gz2Z=NQY9K>9C*x4)|Iijn}ZTyS4QimUgEZ zuOm2uC{hOLtjS|rEbPPP1?cZDI za=$zpFViV%{CB?L?CQoX7|k25@7aD^t4Jf6g3=wT`}n<=<+x?pyUNU$RdUOul5d6D z4GqCdqvlt64CcMY0N7Qe&{-$Pd61+20{_`J&F1~PVB7Hn?;)teV2XpXxF-a-7|=*` zM!LVhk4RBKuagJKY4B~DmT4jJWT4-E1=t#kgAV%TjYM8aCthhPgF`On^J2fQVX?+SN!FA4#W&6)tKSp?>=4+)_|ijo@B52iwbn!m38CV> zR!RgCsR|EpNZG$`?0tujNEX?*%X*zwOx=B({k`fQy{_KeB~8g)Od(J(<19$sAt9j$ z%dusKZ+gwiPM1j;v_u17$EMwwc$Y;3dOM)0OTcxL3>XWK9}k$RazUgI5pFJ;zsANS zCA7(-6@sR>EQZpbJuHmHbCt0Xy^BE(9;)lvb*>$_jVKRVjgWB7`ar%Gy6Xu@W zT){7(6yQo3u=(lk3j@$R^M>Q3zpfUs$mPMH?l;>wB>RHSBW3Aj81hRKwk z9`pA{q)){HFaz|Ssq60js0Q62Y*^)w!nNSU7;V8%? zG^?U9@oCgvctnEu7Vb32Zg^(+cWQj1+#Cm1H00)7gh)RK3s+Lt?f|r_`|G*KD9NAE zaRYk7;OxiVi^+Kv_Ga9&i9H((Swv{>rJ^y~4KLRdz%kz3E&s&6&4TCPhwQ64X9Y}Y zC}?dm7(!ynNPz`^`0yb=s3x!e`d+>Iw_frOJD{yKS3V^XI)s-J43{rYW-Z(N(SLy% zfK8|JznhqNoSdAkJJ6T*zY0H~a6t18QlQ4?%*4r2_UV0kIo73jR5tDP??>%kPzXhS zf%E$S6`eZ%_AwzObhox#1ffZlvnetW27jKkYkr)<|CHd?_nDc#?U`wKy^V($G%B>N z%BU(Y7ZiOcoBRUmfxU%$SN?B=1OyU@Nh?gJ`G6Zr2qPN)Ce`i#G5Lk7vn%)7-e(KP zy5_$!&YVsxLHaD+z37e0IIhJ(znNjF<>nUi@e#h)aOLx|X$fkU3hyumYsuhJMRviC z0ocCYBT{#F_f$a_8=b;kJyW&Hdb*r!-V7}6l=KH9Ve%;Mo$c*hcyitFsf?K8Bt?XU z6(AA?|Cc8R2s-~S%4cnJa}lBsS2iarZ1Vf<_zJ0|VTIn_e(Azp`IHK2V)zsLeaxa_ z7;@4$$;9(wa>H{D|2{*>AkmaS3_<^c$wX=4S_j`T~f&jNuUYfvNyI3~^)MYfF>o9+*w@)=T3ISz_ zSdX=99q8cYSXrfS0fDoy10s1Vkh3AfKtXp$QEAS#!spUsf9B;mCdTRRoG2g*ulcD) zlBt#{RMKsoXm8yJc=6(kR@pn>zcno@ZJ0Y>*DC2yf+QRU-QV5?oy>}ajjTakJ(G5K zFxJs8k>j$+GS@AgM~2P)2`v}qNTLsXdL+3AQS2guO0Rz+^_y;Bcq5}B zZ?mW>M>5`IWe};E2{+s@xSo26UL6zVahZnA-fTCa9b_2pWFopEP$ zB6A45xFD_aXSv7ysOQ9JxXIV%r5Qr9$D!9AETR0=3RO|2xy5`-Zs@VU>t5Ys)%-#$ zB4YUX%hu*9$R<8-eq!q*CLsZZHSp#0L>Z?HfQZ18Rtk%cq~v=j_P9@lMgPFe{}TaU zVchR#VTE)-31;H2CS{8x?|2$Q-z@VKjbI&~;Ln}>1ycpbKDdhl<5&|uI^#ZIB`1kz zx1IY{XF);9G3UBc<}feDXFv6>eI7{9AhsAzG38KOSOp-_&Rl!|pF4`(P~xz=Kf&);Si zrJdbkA_*P#S|ePJ-PrVU)2UgVj1^R7pb9U4 zGcP9mH(#;LryZ&38QwTLJUVvV|Aqzl_S+A=4+_D`3~mGCv;8G4HWE1|BB1EN%IMEF zGBVu<$mXa@>g>+a_fPGq!Y(0NLg~(X3Jfa3B04RJX5{QNil1{zLGJ&5lG-~j+S_d` z3~9-}eZU?}gC;N&XX1b!aR$Q9twAXQG<8F>3Z1e^JIFyc;!bi9OoKHU^2W{>TCp*> zk_I535u(9|>N+L&^&ZvNH$)wJtlQd_Jxzmq3iOk;KgT4Srw2O5H1Hs^1y~=QqmP0l z<+Hj1L0u7idajVDWm>Yt^6baN1R1MlvDrdy_?w#sRdlUpe1&Ho5Wh@JO#FR#7(!Dv zo7b3*!Cd36@SsaE9gN+IDFX$8u|7!8A+*w)x_7ZNl3#e59iMnx5G$TT`A^}36)32|uN1PdF z+ioqPqTEV)DydGUJR+P77X3q+Dh4q?Q*x8xdbZE++QPJ6n* zOd8`IT?DaK;WMPgBUQt;GiT6ldO72f*lCZoAn+wG{Wq?LEwC7+pb-= zqrnc$y&k`DJA(Lak(@$OeW)ARaF5>1KHva6jQ&M@TscnLx6;w;H^BF zuR6P*-;l8M#|~SW!S_62$M@^y6NMmpYs-1L?LTl$2=YxmefoN32{!%L4KqF8XViLF z<3nByqX-!p8UM@t{64+9y4s{#i!*y7%RH3Sl$!!c^8NVnEyPK{e+pn-m};&e`Berb zU1q!{@@o~`JWb_w%(mX2#igHErBbX>FtH~+&JVGF9PUJ~bfuOWjQc@Fdo|XsKY~5Mrx^U4mNeNYp8r{03<)+xU z1p1rGw`~hX)?m5>)C+pWVBn~ofrvmfrkG$5lp<+Uzrh#??3H>9DsVupGmina%9zvt zAg`YzP=IT2a^f}PtCwbGvEYl%iu8$U`L`irxzwBUp9$gHJWcG}Yfyi7J%z8xbh5lE ze<(r)bfXN>;9*LFapgI0a#$YtvXEd_q%d?5s&LI<)XH}dzpRvnwZZgWkgIzq}`Kr=eqB%rPI0by_>Yv2Cvk=_a;svgX< z&p@KaHrSEt6~6=tIG2#|Epl~_f+~l(ToR_1*P;YeAq58H6B>na0ho~><$AcjL8_;W zn%B9ORcP#0OhRUkx9jgO#KiOf>f5DC5@0o5hWqdun^q|;3-{<+q8wxX)t|bR)y++{ zhI@`n-PYHCcs&a(7B7k2;Bj(!XRYt<#3h=vGoVh>&Bn825?-EGGHLe5u3)18k|5F; zK)aV|@tXxlk(VL|ptE~dr(K69CkH)>K1d)paw107)aZ>Z9$wdDbzlfF85C?$aa2b8 z-J1#J%}iNQvh3_20U(GJ|DX76Ek+SoUv+8~IL^Qkf}Q#%0d^qb2SXIOXLLCBZ6Z?pE6c@2c}qV zpf6xtJ)IhF?woO(y$w2>rv8H=A;t9RxRBGt`jt;gZ+$*h_j?g0Nrks9C{+aC9=`%*B1z2X)?T26B&&V63t5(o`52?!=0@@fIEr2dL zWk^ZON{k>gEbQ>$rz!^|X-k^+E`#NcBx|@Ej7|{MeDi-eOUnu7QYgjk~gqa3@V8SW;@z|sWjZc#Kd$5<+wZ0hLcU6Pmt{bq~1vUGW_3u zd!Oi!e&(ShYtm@tNqB8$p{-IEfnAZUhm)od)Mhky5r{)2;vQWQ9$tH}zl#|F+2Y$x ze_w7-)Zo`lBQIPCu0c{WpllLTJ3csDtLio--)F%Ph%5l|9kv*VuqsTxy`%#d@j01w zQy83myr2MBD1~BT;NY4GAjSy#_V)ks_n}R=Yt1=xWDTr(l~q;B9}=X}r_*ppA5*9& zYyd`OS~Cq}aqYoDaMuFNM_})Wn6%41`y)|MSeRc>@O9o%dCt|T`RqoS7I8pZcU>-% zLaLy|>>Mpq7MDGnh12sv`+Ux(7`Xw)7#`6d#GHg^(7y_o)~;vEiKiF9;1+8?a$wmG zDe+ojMKY;uP^opph(PpcCnjcAWJ-0UFbNzvlr&APXH&m;#kY3QITxA#~oAId;eZQjG*u z02N@Z->I1?`hz<#DcutLIibX`9WTWzE|^Qe6O|)=f7m5l)~4nuRm4?NazL?%D7WOvlA67I67g+};PiB1lCkj$FNyXNv#923_P+;~>E%z~ z;4q7cHq5+lqupOl3DU0o950kdR5;oT_7tf|>IJa68UNVmFs{iOmjx37Kn{KJj~Jt* zvjqd3tz%S}q`QAUH(L)~*4SwgJZ5&H8^%84*3QzyRpK+^)W?15BK%3oYHSy!OuTn~ z2`7_eY>Y5M+^YEvafKHyX|&UwaWHsJGEX(_bzsW;3CZ& z-vDDEq!>C}U7o0FY6d}l3mNVYh{kN54j*5DoD`hH!{c1;rrev@0yGcOO{%E)D64Qt z0CxXy(LAVd=y4OWhJ0zCf8UWR83!|}`c)>>-uwFcMmL3YIMnG`3xIpZ9^yciw3I%0 zF^NZ&|1o+0J_sIwL^-BMV7fNclu|aP+rIGXXCi_`R^{6l*W~h3YbT>;c>;HMa4Mae zNbkOrQ(#I}_c88k3 zH87Mk%2{k|-_r&slmP`AtoY=DhuApS|5>h%R|>WP-2vA!QaK1C-NW8K;Oqx`Nvyky z@Bbiu=ltQ`Ei^z)AND1M+G9Z0bzX6C^1X|>dv8`hd3N_XO-C}x2U38H=v#(gix0S`UsrjIOrv-ihr zIb(K6mZRw#HRKtdyKK}#CbCw&GmGN0BVvpII{U#Cj_18gF1cqSq6>a%*4#u(g@ih?O&_Z z=z7b+nj&~fgGbD}=1cnp`F#%F4#y?@_#q-SNhc~H!IjC($+vz}pbeyONc4?Wofmn^ zXvm})L)3p0xHwdH&Q(qecwE#@opGr?ZRYFo&fV~03_a27bD82hI9m

L{?0AjcN(E%PifLdTAo(vKVdK?k?nP6clF-`_hStWqo!_35 z3CX(y8m#b3987!GHw}G^f6(1FvC6^ae>(oMr!b;rpL>-0XHyA>_>8gath z23&X!L@WaAX(qL}Tbg_`-~2t#3;U|8+{EHXhSg#6lzg1L{L-AnV$sgz{fXTZS}FlY zdA{dT7nifXaq!8qtwVDSSCagq_jx>;@Un(mPir53TB={By? zak{Z&TfVEX=4CEQAPzJ5fEBMWGvpmdNz3(?3-M>H=@NGcHW{>xT2x#%&Ahz2Cz!UK zd_45Z%jgw}7?)Ed_7`XAM zxH0uO1t;u>XtcqrkDr+{#(nBCfVk;im`V_Ar z&4F2bW2sMzx3Wk>^P~4Q%MFYM!smhsFYD}DX*E~0i)UOdPR*)S^o3|F;luj--=O(7 z(N$|YD~#*$OiK0mACJ5YtU?t?t}3`A_2nT!175R0qaYcDkOTy>Ab9^J;)`5-Kx*CQ z0`Ng3HwdEeFE$(|Wm;p7ZCM<6n!?e; zUXnd7)id@7eKf&yM`x#SP4)qkDhud3Vxckox1TUN$a$B*I!WE)#|Xob_KO!UPQ8Q= zJ)VI*6dhzejh;{VQo_gj5=QGJJTE*@CUzz_z%%C}flgAW-eie=@QDhNt?o)TrGs4y zl&O1Xmm~FtqmII~|A|p(;pI}$y!_piLOop#>8p_)77L5{s${q-y^pDB+d%#5;xg)W z^>=oDK4|BGhzK}-`9f3v{aPd`$Cb>wjw0OixJ;HeyOqLzPn+Zvwkt6ha6xGE5g1$~ zZZM8j6J(&URaeK8fMnDPxbi7MuLNv622TdP%uc3xfHVg@o68PGoRmq-t`f??e9q*^jlw_ zk&e{Mk@S<^;uPR&Yo30!@*Av!z-m>FmABS~_7Tjd2s5h0a@b z#J%5wX90YxV#fb2hFV&$&J9u3(s@MO`=lj8|4om|VJe~LT$obDsu7~CRegOAu$oR(6T-$=U$(<0KkXq}%u86lA>Wci7q_;Fw zNR(g($d2Ln`6E8aAKGuWb9Q=f;M=m^T0o(EQ96s=V^V$<*PQayelb`|Oget#c<_&>qAT6OQXH4TlcsBNx8cA!;_{Q2js&7V|M!aOJK!99F6ysnP1!B(d z{6_+3lHC7LEK8BU8K(64_7qgZ_bws(P^4KLX(j2p<$0NJfE+s(p<`E}AynesB#ezaMz z(MTyUOjMa->OOgu>(O=tSJJdVEvXT6yHN3h+PTWuxtSHPQI z$ne?f&slpuRv+IF^YhBU0M$8sN|OH8)fv74g@-({31jmP6IekD&aRbC+x_GiLGNjg zE*|ElT$4aY2b(wmGUp{gdw?7n+{U*2Fdc$2di*Y}HT$!7zd}Db(n*LCuw^nYWBD6> zpL3WmAo==h7PhT3XCazbGB*!f%;)}lBjf`^n;i%QtKPD$Ig3Hl8A)g$3?XRBpmocw z{1#V5ym#*=*}!dwzVfh1yX^AvupRFm)YwdEJVdcd181JeFpnRomS7Rn6WbpfA`YgS zul_dx!GK_~f+ziQU%q?MOBAcq7R5Jpn?+dsEw&@-T0P~5*#sHy5n^bnUhq(o-Z(r# z0T{MaowxYZg0ahw(!;m7Q{>=^0fCz}1qnxPY3YZa9xTvI_3BHE3XHh+K#T6wEen2>qc)zGw+|z4nHqPm1{1r?CKw*Ok*p!dr zb+%q{Xh_IU!eoW$@1ghonG4LBz|#oEF(jo*L!%t-om6-CSmL`}+=9JJ$F6X1uB~oM zelUl$-Zo53`~vD1JTq4;MhuEKWs-_kWJ3SREmieDlH1au>oONt{#cnA=Ktdcyt2KU zywx<-Vd#MvbB!a>UeDzPqmt5ej{rX{p@>NgfxGtQeG`1`w8 znQz^|NQ(jjXE(g%?+yeu;HD|qIy^KpUgKW*!fM$_jfY81t*_TOA?fap1)!4o(R$9$ zF%47hwg0*TD)k!W7A6nS+KorgpZAeKpM`iDlI)O*hdF!M-60Q8rC}_&QpYk->!7=oBgT@8zu138S-f@cHAj}u+3JO z4c`ZCLgFD>sa9C6UbU^#;Mq~!h{ZS=%T1p2>MWTIEg~53OTEqrCEs7x?&~o`j}x#Q z5#ZtCUYm0e(NsaHmN6A*#giBt-8^Dtn2G;@&mY9U z=H)=#JxbDDIZ@SC_WL{nLeT;b;+}G$sy+p1r(HnBNT=KeEDI<%QV#u0ND2UWjp`BU znY+8Qvn$~(wC}<99}J}$LxEM{XmZ61={4qoWwMejzO=$z=7dhgZj)Mi6ybx2G+JV; zd7Sgroz1+;FT{Ye!h-6@v|#~&j6(Y%dP5l#vIeODr?yxgST^PHSKO*~p$oGX7A$~JR+jS!~|C}X^6@ZoGMgZe7B zs>q%~HOiY1HG4VuSY}D*nNshcVm7KNbTd9oyBs|=RsDf3nm2EYbgPw=)dSf=#Q(hh zQo{$Zp79%fV`)NksoI3%=OwfEHMTMZ5cZbk%K))bdKPJ+9)6@&xG9Yh` zh81BS=%+oT&Iw$8uMz9NNe4D)HIXK0M@N+{zTSSZKC~w~ExG;27fD~vtNK-{sdHV2 zHA&dEGC?iZ?be{(@{*b)2ErqTqOzpi_w)1kUH^zri3z6EeI~gWtfU+>z=661AOS5Z z?qCN2m$>RI2x<~U(EuRxL)M4gLqm!b>SLqI1{$5;(#O-9*(znmNiC3?;DM4pKyWV zflt5dA>?(i^DhFyPVJ}pppoPh3V4fMeFrg5`-7hKekEHni7sa4lzFz20RU82c`?pK zd^5nwsDQRzE@filjb_09{r$N4_m`LosFtp5+yKHD+V@EIDNf~$#l2#bTLGNBk zsLG_9i!PS*<%I>tjGUcvbq^0uivmt&CHv+=Obn11uj`u9cr1tZLoG8HNg@}V`O7K7 zEQnGpxluezv(`g~CF3K28AG0gqfmqy=bQuoPl-l|O^h7x16=bn2yBeF=PRdQ3#LI4 z07k};6f;%l%Zk_M{p1lDLPfOj9#Gu$qWjGaWHt@$YfDAJO3{=TD>g2Uk@WYQ)MZGN-U=UI+urI}bI5h=>^V8V^bwoq?Bp%_>MV0E zQz^y6?f`ddCC-YMS25(6fqEQ96M6aD(FPg){vndU1h7cW=1crq*mHoGJD=Tvd*4S! z0@~+kse+BFboTOG`zJ{}mKsgU$N=_0+>c1@3oKYVy1MS$fh%v8mNbzbT5YJq1}KXY zy!+Pmq44)eDvqK{kGZK2v8X#=(9YzJo`p>qHMeDN69V6?K>P1$*I$8{(C%yf(ko3IdiNi)wO}XPzFT-g@ zDgzY0&&&)!uBoc|DMQTX@eQYVnPn9c4rXS=`+IzhN1~?wdSQ70S-Jt$8+`m2bW$oI zd*5lC2x;X{idDKa#hB<`u#t4F9F)CLzFD(5+1{&O$jtWe>y{(p2YNRiz_3c-(nE53 z9D#Sd)ewAj=y?yY(him}MxVHk%+tS;$*Y`?4jS3|_|tk+?0v8JGx=w{NVRiIY7(CO z_6WV)X$I#E=;bm%2^<4TZ4!1JaZa*Ds6bLipE|($nZD(7MbT?n_jWkrz1XKKo`tDh zUEBx&6!VTeE-}&+YLw#5wev=>+S}Vf4g+$xD3r%%H8tW-Bl-{vlyWU>S!#BfrlH5E z^UohIklS&R+iUepVx0d)Di0wBsNIUU;J2h$0Z-q;Ua8k4phpGJvSM8QbFt1p+m0fK zHN3TZ^bYTM0w^m0-bDaTDEPv~jSOQLSy5#RCFDO}j8Sxi^YpLJ_mTtQtXGN~woM?y zuezE~Tv_c|aQW7H)q6J>u;L0e=wxo}Z2OYBrKf-u0+iTN;G`^n%%d<(qzI%4^CZsi-GQETKVQp(M-?AwX>$-vr4n@h4|=8{DPf|;SL9KGta&oGtmqW_ zpdI&!b8~R@v1@(()3uE?QwSwo-&Q=Egd$lOx_4TxgaHFUrm?Cgzn<&cvqR|=Ze)as z^qOEfR-WaJ$4Pd>asI=0cOFbWfBr~ct-6d;H~p6$vv*aKVe~2`S?jz*sZ$r;!-uS( zACHZT&rD#@nVLcZBp5q7V6KJ%2->VdpuzCxttKZf?WC2gkzkwWn{r)+qpnty*>bHp zTVt~0Ryotwr#G%wznc6i|J2pUO>lHutjQplFlcisG7GVT$&6W#V*@oQ;|r-0Xm9=U-D&!wQ%4xo zCm|H2G=2VJp3@=*D|GT};Ic*Y#gfQe!|bIXbOTD}5viu287oi}u$srIU{NOT)a}dL zpYt$%$k_S1fHil7aVOAhq#taDXaDehrD>P;i~D`yY0)%rhblB3Dm+Yxk3xinhV8@Muan8q*sN}RDpA#z?<2bu0XgieWi|CvdrWX9oZ$G+@si=Ds6LVSU``G_ zHNXmjnkYH>k&31vNFnIls10!*{kvQXv$!ca^;$#eL)YoITOwCyI4nxpFXD;vBMLYn zrp7+yi4!=FkS!KS8m6o}DWko?BY9l8-zs_7O`O&U`+qL!vGezKnt(79cHCPM_eZF_ zs&+;;j%?V(;Qt9|4W!y2B|uP!jghC2_9yb*nJL0S;!z8JgSKC!njGODO`IyRSf@|zwa+hZB-F7^{Eq;BX~5-D1a+%vzKJ9T_z_r;1Y zEgr@sz#x&|h?bB7e~zE3?o?2aRo!!c2!_WT7UvxYxUt?}2~4o_Wv9WTxB zvtKahr@izuMM#2&3K&J43WY&?th>18Bh=^tq7)?Tnc0%&K5WQ>GZ zUc$467y)f1Lr38)M{~?o*V4hzihs+04#Nz5h~O|Yt(hdFq@HiMTFHRMHH(fA#;d_z z>jO_|I^7@%3tM|`sb=n1eYhjK5R~jVJM3~KmmWn zAUbzASy51`zTuq0zGEefufTM`OKH^GNd=-jkodqnhq==b8P^y8dVh1Wl2FWIveTr@ z;onzu?1KXqX6EM)P>s7^aUfs~$lEuIk@w~=&JIBAS#3Yvc@`VBka5wIQEE9vgPc47 zl0=h^>#a&6Jq%dzV=2eJw55j_F?SEGKxGut1RNE0XY7l1`~FfN3mco7>Toy{kwkvW zJ;kNDfzE8R^XKN(JccZ)Pg3S{L1V~GaDe{Z>AG@VrL<&BuxVFB8GqG8NM>Tcx2>Jp z(GzcQX@^Tb9y87Tpk@62N>dBn9S=A9Tq!qhF1CDNvsv#Ur8S?^_Juo$`92qXrcGV{ zvI%wf--3xM-JIuePO&iCdD-ldL1av}XkCmlvWw>;(gHgs-G?10Q@9d?#y*lpW< zAbE);VdGonne+K_xM7kj)1}A2&fn z3w%?$v;X-1e-sCsZgp73)x`?%0|I`tb|=D4VYUOVB?m5QeohaXgu+QPR@loe4aCQk?3#w3C5FCcpLEJXL`* zE^bNa=qHYN78f9px;1vjklh)psYZKqUac#++zGB_I6nZXgEmmrPm*sSSj^Y9ZA6c> z^=wnJ94iB6R@hro0C#HpyR-7X%9e$Lm7eU@_lXI9b|Q8s(y`yeqUsXpz%cRaKbo4F z0_Gk-y-^64`Ezh~+H!SrwGUkRo~7@xC7X8nJE-YFve4nJiV@)Fz@PdUU(QqEJXSHR z!_Gqa#ZA!OH(s@2f;|Yl!98H!W#-@jK){%j41P|yZDB~V<5SgAdh6yG9Z_7InxnAv zw5kkG^Wpb?jpRNw?MbG7J7w}D^BUV0T6s(tfGU3jp-S@Tn@ttB5ck)mF%7Ra+Iltj z`?_ng4FQ8Lo0AtIFT1%n#B$4C~2+m`Z|YyLO~H!bkW?w5c2vCU6WJ+rW~wApcU&F}p=@;IHDZAt;Xfj|y>h<=Awop7k9hyU~C zM&X(rIl<_sT6K;rBByPtXg7K`vdsylq@=XV&9E}gPrD||&1Ge%W(RqOo^^qnf1=u+ z5*-~~=<4EN{rz#TjQ5|r14EiO!ytzZavjVfyAF~-)!uaG(<(J*WfLv@0QKWGa8aTP zXKkz|N}(MPLl0YA>Fb5$FKw0M7*zT=dxuBNIp)5G+S**v*$bB^kq)z<%m*8ab98L> z5RfSSuQzRl1k;YfRw1 zxTA7C`(<8C{FsIijUq+q2)8;aG8UB?b;|{ZWX`#cjDn1T3Jd&*9D4}b1n$9I&`s^G zW<|nR1+?lJrADz{&(7uV9cA$Bg0~Q^Wv18=iym}5TJl1N`9Bgi4_OhP8TgVwK@1*y zhlUwY-(<(rtM`Jxg)F?simI@~|MSS+Kg@eZd?`)_C2~bWaoD^Sam&ku!&&C3vHE!= zrTs2!{c0*HTb6enV3B+Q>WGgm87qcfcOu6NlRpjeE^}webNAU!9!k}9dV!Da=j)ib zq&_t1Nnu@L39(NEFdiNr9sRGLj72_b?9a!%223}<6gW0ec0QMO$kY^|LQ6kh5oODh zS(*b0!0=B4&Yz4MCx5hn$vHRO|d%pPT_DAq~WFe^nSq0_Mmg(N{ke7p41t6sibc>Au2UyRo z+pPR4yrVy~Z-7n~C`2<9Fl=?W#(EYJ*{bZ}z6HTt=V8$+nN>VbfCSuayTkX&V8|a` zot$W(q&d}EVG!a;OA6bq_=q&W^_GYA*mYV| zIj-&+Ki;RGUZDt=eB|cL5cq|N=-qu|Nl8hEhF`dNxA&1+`lF3;ks8j#)3J=^8$?An#RUVID)=&nuM-f-&_MgMliV+}c--L%5 zpjYo4+%6R{cjRGd*F_=`rPMpB+hbc#xblYO#VoHThE49ZIac#X$G9oSIJ3AGT{e=b zsc8YIXQv2=7BFxsld41O;klk|_fJYSERz5Ba|;Sni@y;`KB(w#K%Y?0%p|HPOeBqK zM>9-4s#b3Ln2hd%V~2N$k*&530|3>H2E-_q7@w=w`3x z@v#EM5TqEs*%7$X0lzDj{+L$ubZh;7-MdsIoE8KkK-#BcW)82iYMxWy^UFG<Ow>7Kf#igGmGS9=5d85PS*!!_Mg>o>sDj3kzsRjakU}p z#FOHNiOSdX#f?IlEOa)|=?E0eEi@20*Xs53H+AOb@>VkvO+aemBfa`>XV7u#wJKU| zH~qD+q)A3X8(lCh0<=wKKxt_d>Ev*W$E%@z1+4=L8U#UpCmsE6c1O{va?or97Xxyd zZj#|*#IqU58T1Zl2fHhg$fKeO(Ea8=(IL9He_NijS-wWJ?9=Q{*CX@#|HMD$HR4VI zggcSsiYo*4D8?WI=O7E6B&lE3!q$yXi8G_elW&)yk6SX}dc~xWJW*~fsilwae(F-? z+dpqTn^i}3hp*Vhh!eDgEU zym**GgEPP02T?9Kx~xBaO`5$M%+UU!eV)^&MP!sOBa!G<1gN{&^uDEopLcS9iC@1* zI!o(e%+OYER!K`_RFv}9c}~NNKfZr3MNaWx6B8rOo5v2nEL_pt5;o zbW=Or*>5uq@+|w}*}-B`;d|wS$jq`Lg=L_&6kllf8p!MQ8(g7_@+%S4KfyyW0lPm^ zWd$+;Dg`d}-t0{M)!2j%lTT&&|C2R6WWA#*lJ)jslYwIE%0hn<5AqgAGGgILQzJdF z!-={t-LeCYT+rneu(As5&IkQh@y(?_@Om=-L5zI1NP?%(tmB5=ritKl0t+uZ9??kJ z|3==5<>D(pI%XzyO18x;p7~_y`Ko#&DU_v;c*y2z^Wg7ySr3~Hnsd`WO>X#fRv6-`(GlfGx)q`FOqgnf!GO#8&dw3_OeKT86 zA~vI@Z+~&I+BLhxlX1om+F^kOyJCDLm5FEb$=otdDMJ;JrU9ZR&`$??4P&?3JF3)i zQ-oEHEfT2A>{_zW$$q!1y?fdq+G}v#GJ&z?;xJFd+|ki-@S62`1+AWoHv3Ity1sH~ zEZ96a`)8OjbmFcZ?^%2tAaX-$#PHJ_Az={S+>?tRT?~`P@q+-4ARt8n%aarGsd}Q7 zNTlj?NlqX5IQfj{uCC8kpV9XP*QckGLk1>rPS9~|K*ihkaeM^eR7lY4+ar3wnbe;s zzswsx1S6^-DkwXq+#o2)b=Qe2q<>5dn{(}`912Tm8n1jbinaVYEa+oH{(^QE6rH0R zj75#HCdpvl1ZOGdKo^tK9#GH7`{Jv=*w~jkzvE+9UeZXw>HB=CB8rK?%IJ5(ze(0$pxcT^caw#=;-L5t`Aa+^)p&WmFXRV%m zSl7i9YwW~kVYweaPf4T|XHtYU*hq*v7|{=pB6G!DMv^ocgXHgwC&a}Aoql%g)(jFe zMDRiie$e?zL!r>HR2Qd2+knE$;v~N7nyn;Qdv6*?H;#mfgT-kuO~(Hu`=CXXHv(Vl zu1uUD8(m3^CXkOQ=g*Ke{G65m&FEm+W%cO2Z8rs$)0=C>nk@FmLp_h<&B^!oQ)~73 z1O?x}ZlID=kOMUy>i1KJw@?8$V4+$Cvjous5qvQ(!QS(Rp*MRxG&{!Pv2Ln;SvR^0 z_XAhZe70vwd@-!SYnuFGV?*qat^X}H=nc$3C$qj8q=sHmcl+X%wY0heWfM4anGTcC z1|TqR0peJUKvD>ON$+1^;^!0f!R*^QBk1MnqWSVOz;kZTsNhwborkT z`?x*QA^>_biMkaE3((6N9zMa|VE}v1Nn7Rs@&-|3epkwtM|ea;Iq24fp#inRXGZX0 z;s2xQtOBZB+ir~tDvF4Jv~;(Cq;z+8ccaoEp(03%OuD6|yOj{>l9CpXl9q1x@43Fc z*U{1waL)IAo;$|4M#0au!yjs@k3cx42(U>Oyibu^|;fB z4Kzg6xGqz39qC-WA1i01a^YBTzg1?fhpS#(PNsl53n?>R0V5+kjf+6L#ytM*!e&2S zN`rN;>^k+*1<%I%V{_qSGZ<0xwc|Yk!cON&GVw^)teD(<)M-3 z_~9X$^=vFmX?S^&_y_%?ZOf6M2MK^_AQc4rUZ3p#;MllT30vi)0_Y@QW*LKrkE0y> zlaj$7-%&bdZf6zli;IosD<)7%b(fHce*Rh&6E&1wB3dZiP4WSeW>{u}*s(w355R7m(GL``)0O!o{;`NrI9BMeI2#*#Qvz z9|Vfc-Ml$|X5@?d(Rr?qLN_kL`)peV`2Ey6OA5sFgs%>3XO{gY_=c% znvu8Fz8xOZ`htV-)$-)Y^oy%o&<-r#p~i`%i~c4b8dkq}G(8DruI2J_HFp(S+V;Dh`@pveIV*B665Xp(@e1&pa%NYNBr zjWX0W{Qg3P35JcHAk7@$=0UVIoduYjid^u zgu`ZH%l%n8L*;wEX-wx_H2<1a`sksNn^b5dOJe3FgRAAH$=vYLTP3WXd>A905xH_hrGVTYlSkdn}or%7r-ybj%9Dp z8D?Ri2exZ@rLImTlrGHBgegs5$dKo!Dj54%Q}z>U7xLc5H}ZLVRO8;iPX#ZDXxwCt z8xtr~C6GK4G&G$)D@X~_5dSX2{JmQ}FF!wjAtQ3G$M<+vOjT7hlm)T+)WhIh>*6%N zt%Qa>XRqJog{YZWxV5oQ9Q5e-qD{m` z`-{2a2tA^ixGg?fa(!R;cOMx2zz5r$KWyNEMvBk~{{KC-?D1dMhVM%$8Lp-1Fdl1Y z@P>lsPY|(|LFJXs$K!l8Fj|eL+CP1+O54sBT{pY(s zaF8MJsXIO&V5fpqY9NJbpp)`i&qo@PB(jDGZ@hE90GTEZozhFB8kZJ_=eH*n9Pr9C z;k}G)u2&acNQXU~;krP!>eVj#jAW617t_6M=Xo@L@nz$J7^JJrE6zZ z37eN*IMKkt4I@TGe0<)zE+{I9GMRcgV6OK-cjX|FQ>XYBpFs2=?(>x5s_4Qn<`JD; zImzGSCSJ+v-K?n@SQQ*H^&)bV6w0@%CoA&d{1d2sVGX6Ns3$A6(TXK+d%)rI~ zHd-XI!S8?$vgnq zE#0f$_$!>k@$5=T?cR&!_4nU?S+Z{>B<$pRuUIcq4<9sw_wDQ^>Kz*yeK1i2)^C=)*U~H23J2>@>4lk5mPao4y*c zl{TF*!dMx_7R8p12yg7g7K5rFdx z1VW+(hw7*F$bP%!`3!N83Z-Pu8c^z4wuZHv!8!p{;V^v$tIg5YbSF%@ARhLUU6D0+ za-OXcu2lz2m<@DfAm||=-{PzuB{Ff_xCU!_k|1Bof9~3>-6a0< zrirqCnhJ^&B&QB_9G^Z}j=lZ@>4Biz3#K*@J=G4@JngSXJjN1W>EqJJJ z!K}OooT?_b`!IcgLctXw!9_$v(fe28QT#}E`C^1fIGiBibChY+5I$)WURqEV3LkP>3e+~9 zFZAElH1axnyf=IL_rT=?rXIKUsY~vFZIHFWbf!P`vf;sc>7V*bc!KuisImLsku#5O zJYb5>at{?8UW4FqtSFh7V*T+vyx{uhpTBEjZra}n|Dh`ywRa_9woR@W*J}3+zO9bM zNa21(0gnn8aMIH=Qrpwb46BA^iglRN;?6~bPr?){D_;!K`J zy2?D}UbFQxt;umo>(R=;{#v=k|5!>~!HtC>C{FIwCKrtpAFDnNLp|4jNa2ayWRpH$ ztpQ(v9fKBjA^|ZVwr|Jx<^**r!48w3`!*1Hf0(dCgk*TDiAds89b*^wDfosc1NT%L>8Wk;~_q|^U`pXYZS<~O5;KPQp(gCp8_&OV2q zSI&ZF7>RweRF#d=B62(M{B{p2b++6|FLxp!XP9J=2Nn?fa zkW8Nb%wuc3mB_GoK<4~v&9sV>>;r(e@bSw{L?4)E-5^mCh>CHSWO!0tQ}f4_ALfYN zfjrpAAUtHdEiIi_{d%ybiy`d9K+H638X#1ARS z06_;b`M%o%W>p1JA47F!9XOzklY#gI(ERK6+9x_h-F)uAo!sN<^_o5-O0`^G0X zA>i}^!lLHE*@cwigXS&~5Ju1&4VT!$SFuO|3V65=K>-gY^ECA%HC8I#;wDShD9XfZ zGRzOa8GvSzm5_aX-x3VI`bMylOzOin&Hd@c+J9T`QjPXJ8^;YqO(s7#;JKux=!I1{ zOh1R!hN3Zt{Q#8|oK5NXec@%&TGRQx%2fIv7@1bK1fl z-8&iDcpyP(3c<6U+x4p;PHrr#A?9;+ko;=t*({YIdaiqUn~?f0Hu3ZM9rpkW%l zUVV18YJ8=fcC|ZFN5Z;^dHz_cNWogBGIp5jI@fXN1%&C6g-K8fuMk!Lg-57_g+++6 zx55HkhB;<_!?*R=3I6}WdDux-@O%H%RMym4r-{rB^i z&u`!;05=WHq)|;k;raDoSROS%ROm2Y8T!Oi(C5n=`JGw{U9Kscb0k8434$~bUR#B~ z{CUqBAH;B$l4wftVen-m*HpYDP`rUb5iblaRVnW#c@8S!zjNd+q%cpqKd;x|O?5aN z^Er^MnA|S~M;7p#;fvf`^}kx3f$sPD)yX1!&`;nX)H*cY^L&mZ*fJY7Xt)K8uen0P z7_|&%GE98ohrsn54{6+}H(lhm)B3-@%ssYRj=3x?!iJw9AqDmcZu=f;i7ZB#+#xy z@PYe)dRVvI3{AhrK~^fWs#?)Sj)&+Ftcca>s^=Ko&z`BOs=n>E_yd}<6kfj+5q5B9 z5ny!1LAyD=oP?*Od6RkuszW# zcsx_IQiuM|=iBNfNvhLcl_Cfv5W{Y=}*F5sz_WV3?mGBX$7U1(< zT5Z&+b<)&Z8G39i$BN=78^ppl!H5-eybvS<6dbd3XgmJpf_{ z>CMB_O5t-(cy(@EEh%3~Jac{yz-FiuA>K@wK;afkB8n`imxbBiz~UU9KgdFiT6H&P zC(sCzF%8EBUJ_-7$eT**fq#82gF`dJ?<6ay2RjhJ&cMD$BToR{5kN^a{R?D!3DlBT z<)@VLajcN)sR$|I&^776ni)w?9)e*NXl3)#{fNNB3SWQbZT!x>e#F~wRBH2_bmv)O z_(SnwTxYqI)S0Mnmq+KDzrVqy8p@tNcf!JpPhMwo)a4JoZ9Ai;j=d3Ot{mK9z%edKz2rFBpHm10e7xy zq}TJ~hs3YFw|l)QcJd{K#W@w3H^uK^Fo>4REq&la6FX~Y^n$JE>5#JDcNkxG+w|qf z!i*OQuY$jJfrlkZhME^dFc4S?hI2A01hxC-OlufhQwxj&kny;Yf=2`}gh7&lL1YG} zn|F#-+L_OD`9IE`OEyAKqzd0L=7o|T5e!}88&Ao1tS1|^ro?0-}34zkgEXB-D*{t zIU;-a9dEHu9=l9tf~mXN`0ARPC<@TjRIqO;q#o%Kcs zsrQm2B$K)$_((93V>%d2gQpLPwgu4AJ>9s|nH|56&<7#;7sxrXo7*$x=ewvoU-vPQ zMkl1;x%*E$#sf@_m|@gqGj%Lf;8N-~xiWw$RVIQep!E~8vJCd3xjBh|cMOs;->H<+ zvgK~xhaxq#Pxyqm?eqBlwltk%~IERA!r`5ARVU4-Wo!N02Bq6w{F3u9?lR%w_hhIN{)4RJ~_n# zW=rtGN=ZqV>#=b07z60}4M1Qt``Cib5L*Z5goK0uA5-8w8g=65Xykb8pVGIHb5Zj6 zVAW`;GBVYI-tkRl=1q(s>N*$RO(-6D-B<#{H!IeL2({hMS4da6MxLJ*M$pxBlN-f} zmd3+TOp&3I;4ydk@1E~PE@!6R5vRKTL7~GCwC;v^+RS(YFuE0H3C+~qbx?Pz8M6b@ zyi^>s?vLS|ummDyZSx7wOSB0WG$~oChP6(v5muJ94!gFss{Qre^ZJ?J9Yc%Kz}G0? zRrm7xW&|#kMvpDC!4gAeCmR#kOO$MHOml%yV?cg< z_$$ye10x<*2!P~6s_VgE@B>Qs|B@hXJ$x==YDxjvBL9APn!=Ux7DMRLkObpDf%r!7 zfO4{P{iw*1uiuIT-8cPbpp2wn|G~$=dW4f@vRYeG&yUKjkDZWG z09{#haFl3hYauhm$O%&LzGZIq-1!g$hDm58;9wmd9+rFkS^!Qcsk{-ICqLC4)ZmXF z)PpkgleeSM^k<4s)dTPSM71#RCeEW_%3>QmM8h)R=0 zhd*wOTFH#zwVRcT!|uJ+So43!(zgz^Ap6${7g7Evz#R2jj^%*>W&w~gDsKgs`fpr~ z#f(__yK^oQ{qWiu2o2q{-Km38qxoICnNrqf)(|~B5wT2KFUOyFltE0effEmRX6spQQy%~)PVo2vCCn_z?=$bqEIJ%j;9WSNM!J4d+u2a zXJu95fQ~1QFUJ=&xzG_pjkd55=^LI5q+75QgM>0;e4~7N3k4L*z{f+uTJJFa6bIK% z@>^n1%o?+d*sPAtt*3x7dHDRLFhF2HOj2plZC2eYXZoyaR?|Bx3Xw^f86`7t&K}P( z9m|YTpAa*Nf;bDmk$$>FH(Bkn2W(04Q^;2@cCU~1^7@=mJ30bMbA{GHx6tiJ3|^_euFQj#E|9DJ8b}u zQpgT(WzxqXun`Qm#vHhD?gf@j7lR}XoIXj%CfAxbvrdzq_f&kMsdGL8g5RNrW-J6Q zmvRURL7xEE_WZ6lpi4IEZSkjT9kYtQl9>1Ss9>Q&@B)JR)zM~s%2r1rjw-iG49kp5 z?r;#bEEhBx`ue>{)VO36q!av?JPf%dK*~k#*^wE)m>&lSpF~UA z`ig5>d()1yH#l+e`Ke0-#*vAg(<4cW;-xPm=qEmY@GsVBbhk{h)}+Vnuo=y}GVI*^ zP=pdBK@`T7Q(jL>&fro1PrH-akcRyyjc?o36#qo?wfNbYRJop_Hb%G_b5o7vHDY|j zmmNFg0yX%Wwqzex9ZW?fkl3x1HFT1{Qeiw9Lh~& z8g@0>3Ww#Y`k18|C%VJKXOP*=^w*Vg!RGy;z0-V0MDmxS5~ia1$n0x#7 z2DI=M>yFN`94mTSy+`a!%eN%69%0-L?EUQM=!EqF=h*=e+u&N;7f8Qk)(3FR=P!3f z5qCSy-mAYY%gP^U{PX7zS9%t{k>^|3ufQhz)dxbpH?#wO|Spf?);z>U~8@OAi$_H8E2^A$Uqm*kvdm-O<%b&pVA# zK$zU$6dTd3ignas3kBetQb zsaB9KziQmKGKsWG>K!J`-sq*w;glQKkIc3yFImYMmk*Cr{x_;VxF4eI^R}spA~fv& zil7t+SB9JkbF0a}>ukLPwhLOeJ>-Lujx{Zz$_z4(4YgY$KjS<>iyII?HRC#h=fJ%Y z{&2VYj#OpywHz=6x73C=E+0S6fo2x=aNWNJc`6+yIZ{~hqcr@qsj*d`WKa-(x2@KB z$wyKUWZgs?nV1weDP|Tcym9Cagg;MkWB&cS*#nGi7h0mtWpnxVg80U;KO`prN>sDrvA<0(hpR4mrXj4wsbb#%^3bYQVu~p zju-~BSoEYG<{jXZ07w%K^B2vR+%LWz;(`AQmKR`K04W*lxM9Zx$AW^r)_0{PyfkO;pr8(6MBEthby4z0K}T=PSNxgJbD%bZW0sRQ0Z z0|p}QDNmJ-kbbMh%|uQDwWnObJYjvD=di~8CT6;T$U|>PsK?h;`WNxyc~72@n=s}F!Nd%_NJxfCPtvA>ufNQB zSq*HJRyU;4ox=)8s%4sq-cT!;$CpUwZ^;QpAqJUYLiu*bXVn-f5|=L0y2Bc8{@a_X ze~@X45;Uk7-rs%?z8A}QajSLi;Mo<`OV?)ys?5JEplqhN`%d#5mlhixhHsEPZnp59 z2qJqv_#<8!WPLzNyG zxhrjUf*-KvQd9d5T@F&6=rQN(!BKf%2hvf1yH5i3J#wSsFkKTtm+k}G`Z%B?jP0p# z5lNPg)0uOaJ#A=gfJJ}WLitlyUDQ1nhDbwMSr(p=xKj^ZG#P-%0PK!|kr^2imX<~e zgXZCx9vlV~huY~^x#0rZrA85eOas3V0fu_`r*;du+|tO1f|hkVe9OQw&5KBm*53zv z)e6tkx=glm8?XgQ${yKFUx^ zE&B?2rYLO5^GjqA0fw{|r&@I|WE+*P0&*UdZ4TT_TFDQ-wZ2iJGklfZLmC?1)=}^ZuWF>_XNlY zfK@A9_o;HfUs*0Y{*c*F7^geGD|*HuihkY3w!Y6iQgGn7=~x{b{chk2_xJ#6C<>e+ zC+aL`*MlzrwUm-rrGWn{(yxC9u8LFPD4C^TE0r&7je={}Fq6Bu*({upJ6`X%Ts8S+ zq`qc*P%7DoaG$!jJFM!}q8%Pf0X4}-xU^+J(G^Sy;tMdTNQhAkqzUzp3|_ojHTH}W zA?NLM z*Uw?FM+PSaEHRMv3&@5h>s{!S^1>j7T^Kn$U;`-b#j^1g4cHG?p_eD-nT6^p0tM-T z1`ox*;a)bE@_It(rj~2C(|pz${QhN;JqnTPZj`H?OO&fk6w!JVYi|s#Km0QAYZ5$p zVhNk2DK|9&YLH7aldb|k%!K#xvk`DEcP@%5E$1pKDS?!>Ot%<>_?qP3?8X?8g*QYA zS#addwiys*F#R^%a7}o&=o|VrvBX^NW|qSE66$Up{G-D>mt$+ezNRc0_NMhS9g*U@ zlC9|%7UxHb3;}Y$fsZOF5&E;c5miiU=a-XAZFF5ReaIQrXMs5I4pE`+u`m7B4_Q;s zAZsdoI#t^LTIN^9$qZSTMVKEKks#O8r{yfT_k6GC7N<(i$*vdueSTaUv~RG%$ZIh~ zB6HS;%TKRz3#)1wQu%nluk_oiKim6J8u6?_FRQc9Py@7R6i)qIR=uAiEx`c9o5~HM zVLvG@A|&PaPbMWZEe@=$NCchVYlBWNBt#ZG&WNNfDjZDdiVo!^MoR-lTZtQVx4)%* z98l_!lg}?MY+G}!0E!PxXf@(wp1#m9C>i6>eXa!Ypl}mHxScW!g_V?u4IOph=@19! zXBi>>Z|&2gqtwb*(vf;;FTXlN9?pXlA<7j5))^TYw#)r9Z)9Xxd$m2iP#;XFn)we4=%MxJN=n5=J6=M4CLso# zK{Z3e*7V9;n7(U8SsgUatgFMSosJ!rr;$8wYcq#l+oU|9)b^m)6pVdM7zc}4vCkUw{F7EEGZ#{c*3ArCuJ6Iq(l&%j>XjE<4!YCs%p)#oq$Tk z)|-k%Njtjhi;L$)TDP7&X^V-&#g1&ZY4%Bk;5wwY6(kSlS9gazaR;+Mz#<$fP5`?r zrAqG)#V?sj#r!&007GwyZd+(96XbK*xyMX8XeAQmFk6mp>?$ZZ|2cW(cXcpA!taeM z-Qz*8-z}#fnlvEMrHjv}iVH5JgTv#>vL;e(BO}HMmjZiP^iUR7MzdGqx2&Q=a`#t} z5{t9Za;uwMITr|)Gx6!BRP?_blD`t)z>Nz6@s1Tp8!h{clH8vwgai5^P{0686)?<; z$iN_7fVS9=mn_44uf?pq%=^#|NuCGeKcB}o$?54SXwWOI#_XJaSKd+0TZC4hgx3>G zHZR%v-PM?-OtzqG&$Fp=UjdI9cj7Q&B6=payqbojhABOesv%`e2{(Dy2DK}mG-p++ zvm{DpsUqi6&_Bag9Hy3VS>J%s;OfDeI*Fh+bHAJ@L!k}+Y+vuIXQX`h+UR@LPwhui z8YL~85^l^TU+0RB;SC_h*e&nP5N?AjIhZ}cjY&4;Gh*j8bMy2 z7uP~f+}BDa&7RypQpG>1la0Xb znxHqm*u-xp$HgoJff{+Q1$R}G2&bYNe=25HtBABU9n_ET9ULTWb1cJzALq7gW@BMk z?QcJ%c&vbyalgUVH=yDzr)BFPYHs}j7lJx}Ss=c*T@dz+EU%CMIM*X1Ve$(L<#ED< z4@cEu6&?dF+c4z)2JQR z2vc$_m|{A7Oq15$SMx!{L=?-^)FC$73=9QDkEPilya8XFAe=k<#p1)(U+ zp3*M`AX#k+_xX8g+^eKh06Q5YgA)mALE^Mg4h{w?kxu1x7~b$Es}Vjz27=Y1?A1rC7i_&2nAC7FC_(H>3bon6(s;6 zM{brb{)zjY{lEcQv8v=$eTyRZ=cwXa^wVOc7qfQN&H(l-U}VZKDUwj|EfK0Fa5HG? z+bC@wAl~^Z{yYlMWy`pF)<(4s-WdvHSq_xWEc#p=9DpwIaJ~jVv(@4HlH17I==KlT z;5Njzs}LJZLi262no)1jG}B<80?2M{6%(oA?x@?Sl+HZchv9yTMv6wq_&9JOo) zT7vtngu0JXh>_J%rpu2O^Do}v&<*VV2`dFCRCRT%MApq@Zl|2=FYh_62eI#=jjZJB zazAF&kCCCi{ncnE4`SMdKjlbXQ@uQR#0&X<>9~@!q!2`mE|zpe&)|2TqPNVl7nvt9 z>B_gymeb$AxvN(xrF}oVs!#0It4FNyAc43-fkbplio)&5Q!ghti$6F*__vl3FxRlc zkXFPx16F>1f!#X+G6h!RT|GV2Z@Wf+#K~)CrS?^CZB7A2<853GcN~kZn5pOuv2|;z z3@rSlBu|JH_1cQyVJC=?b!X@l%PzY)Nhxa8^SkHvJh`pV)YPwzKY{nV+2}>EP=kVk zcwf$=L|!k^xgH*wRqBjt9XW)3snI|@2)4wDQnp6V^#h@Xs+vKc_(P$tk6WPQE4Z2Z zQHD#7G75H0NbWYg#^At$1|CN4aJBecZW!kQ0vy73K0wS7n1x%jtq~H>MPYdfI_1dm z=#`+<2W6I|)0(yAgSQl@)y&;MAcV0>OW^)0xM}k%R3SR& zvtJV{8ubl8=0M~t`0{Y>qOuc3=gjt{R2v*KkEgE^z2=w}OX1oJ&uIx!(^GuP#(^p( z>Qrye#j!h*y@=v32HBHiT`w_WhnMomP*!v0!B6++%J0FCh!xnR^8)(OqB`Q|7Vz8`Hsy1k#2V&jE21NV;T@lh=me-6g z-toZq7}oxd;ZEVF)5h;tOY0iFxKVkLwFk{ecGjy)@1x&7oUFCU5x3!TlH}a>C2dE~=?vdZ6jELxmjoU*& zG%|yw&cw&(9VquBCBw8Ja5N_6Ar07w#Q+_13R;51uM@Z`)Llq_rjI|tT~yLoOE0rr zD$oUkza?g91bqUKZdP0LT4s+xGaeBU4}hZNm-Qqr_j14a&Dx479obzyJdABNj{E<( zlGCMqAXHV@w!t3T@ZCtPG&LR-NywM5V2a1yjGzf#U5*NFuNxgk;03aO3nyQhd1PHv zvU*0y@)GLPl;)Rj;g<`#bKCPQ(fVY5UUbIkIJ|oWL2bEJq26PYXlPtt5?^uGHb5)3 zLc>G(p<_H-<@Kz`8W};$n(IKlK9e?s+(vFngkVp&ovI%+j<0|sc^0E<$*jpSe6~oB z(G8GFWCUE?twV2UeCvHqIlxOI+oG+TsE2i~x%gATB*xx!P}At!Fxo5D78xcT;qg%k zO)oyUR!g>>09QWxPb-HLa@vti3X-%|W%CGf#txa(N_^9LCCTUM2=3WVt&ZH7QTRB< z`8KZ*O>(X1O9Dr5N>7h^$EP8i`OU;i+$DS!IIZf&#i@zF!b;VPuE_Z&p`(IvUR3#5t0R*^hPCHU&?4c6*v3agmm*pr9Ly}(wZ0HlZr7m=?ctMvIJ z-m|+Tw)hSEw*wXy-;wkFtU3bDce`0`US1>u0nS%lzW#F?zxls|d2z}?y_PDwCcJofzH9s4)5Z6LQXUYk*o7c1Cy5Bw!r)!Z8_AbS zg&awsOu{7r)Da60(^pR+{{y_^aB;x0aVu!l{n3EN?ZgnTuX@~$E4$I7m<%X7iK_^6 z8a|_eRKDIRfQ}ZIW>sg!+OUTXS%^pxDvL43XeqU)Dm={wG5yfcD|mza{MA+}947y0 ztQn+@%y?d+sJ-i($ljP_&iARIr{$4%bbN9#-F%qMn{>*T@Jb1E=buX_9Z?*O0r%FyfF0t3(tU%Bf0 z9e_RPgvdS#Ny)Wvz{JEqYfw{(J?AWOrTk?1lh_sZIzv9?0Xk*{7mqP+gZo}l$^-YY zY31Z6SAN=#4qgE1kdZu32q)||?csUcFQSFQq3$Kyi)YDH2?IW6yxuCqukM}6iuy6= zp;r3YF0oZyA>-?-=+qvOf0)Bt6eu?pj>HLT^~hta5^_!3IQp3*q^KYu_AgCHpqm>( zzm-`&25ZRj*P5Uvstqf1gIDCVZ1^n%WQWExVq0H8iJG#S#4*zDQ_l&1wpe#t+G zg>ei4;K{+!5imwIK5QiVWLw>oRd-zYUNmlXrC;vg@+nw}4kRj3I2AprVP**3d%53T ziSbxy*#;HmU*Eqy^u}n|HZ5f7X$T{GhL_Q26m4U0Evi2^pI4`q4`?HYy1 zWo2}e-$R7pL$5y}tFW|}Q5${%lO#yb>?zPB21HOSQE#>lb-Le?E?ALKKFkU|AYh;a z3^p5bo-Iikm5#7OYK43c8n9nVz%CwwL6Qd}-UK`@eveOkg@;^8 z8|S6#3-NFiGg(!>9m!*(2>l7+^e~x`%2FN6z8iuHYpAbhy~cY-0y|g{lGfe&$!Qm9 zYkyM|aZ}Mlonxt;W9_SG()$JnenrK|^B~YeISxS$mN3a@FmSKVN}r_q=_5V%Yy+~b z-K8_7%E`X9O6z*!NuGpyr@|LRH98+h^yGcH3p7Oxp@?)B{tbr{pHrj*O73<}_em~a!FmO_@Idacc)a!&&^ zq;~@S-gnd6cW(dPT3diDRK@=Ozi#~1?Yz-6Y9Gb*%`}=^t}vpWFIGPcY=iyc%bi&d zy31^}sR|qF@1U|7Z2or>%nu!)238shr9(JBhsF|8MxjK1BpLNk=mP5v0OyeWLy)kD z0%I0h@Ra9X2snaQ{JEwD`!58iPnQ|<4NI#<;&5O|U#;%}W#dIa=i=garFfG2pumHs>T2KrN)S3lwIRwW-~2v< zZz0$r8})Y7xsJa}mS|-8DWmA6Kc;~3U=d&!Fzr(hulbmf@n|5mQNhcrn&>@C2xaP% zCtoZ5g+D}+f+1UMSXNh5l`@I|0@wV3Opw;xaDKgmWA5{V#E@=<{uzD4jcB9Nxm-!y zZgd7wdfXMTG=R?E35t#tESA0G2jL~R$!$H zU#kuac+}9uCwpA$KMD}r!%2cJjS!odOt@8CLyu1t#j+xy|87JcyREHFB2yJ2%AXQp z6kK&dG|bP9U9WEjHcl(WU@5+~-f7OFYTVyfI&s-A#?YYPAUdx0_UV6w?G+=z$)rzVm{5s zjKBX~y}IS}xB!K#4Hf%1MJPh$OT+H*YrnzcQ=!4?3<_66=~t3jhws<}RvXTAHpoW) zG{mesT3H1-0(W!TvG!4@#0C4TbA7n2ZdFZn)Zi*)DZZQ2Tq`&K{S4?d2CUMo@mYnH z(JL!f;7X0MOmu-5BFqnb{#PV-9+HZTi$8ASyniDpu;&L^G5X3KeP*b8*)X1)EX~SS zFvA@D70kiqtykr42bGw`KCl?i>a9VK$z4UAOS^4bqOWcWg|vcITm~S&CS`Q~inI>7P#Po}@?97}I8jOx3vU6Ww-={%j8x31==c7&CW(=K;GZ_RjGyH#a-pq{FJA)vz zq>b)|lO6x>SKI->$@2 zu^I?{pzfj%eZG^pmq01~kWQnFt)T?MxY53wrdHdZ+f_}ClZ~uM7hLT1I)tS<>ALq! zet1Z>2&vw5cwxgsLqP>{NC`kYcImex?(3Dg3qFYX$;c{xEQ&=yNc5*TRlswleih3y z@ym3{P8yl9{!-1~>&u*~zia_n%Uj}asZ4%V6onTQ7#I2Rf7{IFnVV^cWM*+~?arI^ z_RUR2s?W;mf8VJ7)r%(jxw<$c;11@l@zus0J11vgCVh!lZo2|)L_z-Zv!89x_qwQH z_Ipore8?@;leq)dD~uCC^UZwfGPbR`(b* z`BRU26F?MBmlDngyEO|93NNYB6{^e z#InSIaH;hAtn>NhK^Xa63l2gstP_wB%%9>LFLe!>Q%B3Dhq#rxlu7z)^QZbb=d+yk z&f9pMm(Abpt-zE=cs5dZ7Y6WTNi*QzL(9z@nemu=B0>34+|{>DdgE4wFqts>8F`iO zrOl)12eA%I%~#`OW=S^-D9saYC-yN<*ElSf5BjD#PS-q&XvZ>mTlTl+%)X%K>ed|y zet66*UEON>^JM7USFkioZ!;pVJ--uAQ+fVS&azrgO#X&cYjffDuYErr(2H2=Ui^l* z#bllrRvQsKdtGf0N9vtv@^fhc8Y3|0)p;DLcdt@wP*8y0^~eYZci4M%oC~9(vJ!XC z%gE={(#U^<&H{#~Yg^$#t8KM)d=b#g`A3$iHx*wb!iiD!n3Z>G8t zn<&h9ySq`#()hC=etEVnU}o``D5-?PJ4z(;@7X_I=FnB+6+V~O zpJfr$08wdwz*9t%=))CozBBR@iw^f5=QF|fNlt6e>l0NgYnLCHLni;qw$fhTV4nrg*p)Z(pq;nT z{dD>0XS+NJu2V$k;tooIrEU#<=sO-S??0Q@2kBP{fOlfk3O4Zf)yax9dh;y?`!oGL zr0H`N++OLFz1WJ1{WE^kjz#NRG;zV^jpvUeq%O&IbP)+j3G;NqmkfZwp(c&I6~|Ul z)NVJ*Bl&!QDf%^KS&^^*XXgSr!O~ z>0FhU1PZHXXgk(nYirEN^f(*G7gjs1-T^rZugv4c1l6L@r^azK!)wf7U$e5Yd4F^SSqS@)UMBNI za0IckeXAm-znz)6(!sJbgX*_U$CHrj1-;z0N3QMmMcqo5rRWidOVz{!XHBg4F`4wW zuXFW8Jr>N$e*ki+L%V5@puaz#=r@0}pI+9(blh*aDhxlzs^2kb-+n5G{ZQy7nc(a! zP#6_x1562Ge)KBeEcnC3?M_Nc#yMAP}=J6qqZ#^=R9l;>%!i}L<#Rn9RbW*M0i zM`eHMTSnYN+(Sp_*g!>db+Rw()O6h2)vblP!#U%hqtGd#UFV`g3JYvFiimv-N-5C859bxEwD7dTEk)9uJbGV8|Gz1$|ThltQD zb2R)rZ02!2G8Gs#TX*DNi*%WXKX0vxU(KcG5EswF4Wn_YGi9k@_Ptw^S3_KlFTXeR zR2H*re>(z>TFBQ`(s8i1zLQCxVapg~TIPRk>UYw%I$6De6{_amNmn|v&SD{vZn#fC zC5rV8Hsm0YYqHh-wHE2}(SWs(B_KIr?ssNw^;&hkiZx3fMY<6gh+g6m`tFp$ov%C-nHsX!sk6| zT>d&u8ngm5I(~(>CFK)6OSFwO`cX8b-A@c(wpjem{ZxKRwvBs=|1hvF-#onTlZD9E z56qbQ=eaOurkfSS%`DG&i&RP_Ss7y05s2JV+O9U@9PDo#aQm{{XSj1|mzuX;k$>#5 z?3|dN&#+y$#ocr?R_Y89tV5$S3SixWuLJ05UiH>u59Zm~*+sx+8W9nJoOx<6wu5RH zG=Jbk<$EF)y6N%Ao8>RWwUlJlaAw_e+iu-pcswF2Obh2>BV1MIgq6jU&vgEhS*BZwOj7QbaSsa zx3#^(HzD_peD!^Y|D!w(j_y*DnZBu;;B#Bs1Ow?x>o95=r9)7tv;nd3qmgkm4abkf zz8$lbs{jXeR9~1hj5rEj@r-cKU6}Mm!)1I(#$r*)ycNt4TGL(85cHyrh5loKvZ1kY zDmwZ16iwy|bM~FZqM?td^b{=o=U;ZN!Js>tytv$Tv}})%Qh~qtGg2Qk)|8JzsKThI zpFh6^H&I+I(<|heUE1q3c1<|@RJ5lXdPP$HA33oI6672G7#V9u2-A9U+InujhYs5Ke?@l z#LkVMDdL2gT(PvX)F&hUJ3Xb4F`HD~Gf{EeH5ot|pI|f7#0hkSu$SkS@=TVmOO5C< zjNV!KMU~W7)8nRO7dTkOxQO+eEl5G5-;o=>B}=nN(Q?50>#shW4vi}754=Ay85U@T#NKE?wu4rN`_h4`8XMvKtt#RknhPMG!D(`!vAizfr#aD@vbPNVVvww zj6m*L4+jd3Qd~n)G^W=@U-I)q;&V;A+o|YZrp`~SWvu;Z@rN~;OHPwryqd^86&|i- z#TbeAC+Hiywdoi!+9tFrMCB}D4XCdOi8J&}j_4!1ge#PulE*Mi5%+7WNd0J)MpUrH zvP~VhNpl3{QaBgwpS#= z8YOaZr#zlMJNm}WGc-FERIsH`pDvT65CqToE%oZ~On68dHtNJI^Q~U6llG&q zR~JXb$W;`k*t?Z$GjFwW2Xrz0c1(x6$b{@agBx~aX0$JE0jc-RLqzn!Bi@D^mLBQP zWXa=4l82gHas*w*6`wwRs-v#tduD#Ke?3{0X zQEpCT+!2EcBw#oCd z^nhvfi(`4nc(wIy^|=hJ)YEi#(9lcZBNR?O z8|HQF4u>091@Z9z8Z`cDz6smAU(NMjfi_aVaQt`$^NSpU@DLQ>JK`0TaPf-v!wN4k zJ^dFu&Ul%cF8*IuG%rz{JNZs~ENEo~H_n+C=h=7U`UQBpRw_RCJ2wm+|l z`ekbxN3VYx9sQ>tkHBeL{8JvgJ?rU{n@f|gmOT}o7o(I1(UM{VV$EQykf6czE+;Ym zBh00+rZ!n!|9u|@zGfOaYM1J8uFkyc=^b*i4l*KBC0Z%WVmM#4vb}>F$c+_vH#7@! z-}tf%x*JA2&`rX<;wCJ{FKYB@#Ce5!BA(Qr^}Ber=Ez@h^VQ%-@)2Nue3tOyc1)^a z;GNc^QS#4fNcCZg8_uBW(f9asCzk3Q{R#8T0ba$hkS@%o+OE}?q7(}y`bkk#hLcE! z0qCD}$K=b>GO!s#4rxtCj}^L%jQM7SGX|(bsgiS_%0`UX$iE`YQ4PuNh#Y4wWg%Kp z*}8a_>3D2eFo1}n#eSCpIgDmgN^%D&&8P0df9L%{2mS{8Zo7SLtA95#U;CT)yADXm zzUgJ1Pcq-@i@IT|t26niM2P@eI)B50xhJc!@kvj$fWszA1y#0%8zLm{b<%;GlZ8Bz z@~GAH8|J8^bAd*coe(h+JYmC2?PjX@Ig#hjd+FKTs7k8&TYNIoKA)2I5nf#DZG zi6tAe?fj$9l^he_Ffx@xafBP>R*LfSTr)FFXY3s0M;-D;64jncHS3>E^770+fPvDnR#}J&w0By!QQ`6O& zo|QwqJ4YG?Y<^(3H-1F`Pc#L?OyPnst4 z3wEq8oEjGIUuNbw7msdMYn#V4Dbo+CYAllz64<<3*}LSMTimO{9i-dMwW2RCXUxh* zsj27q@UPm?xA-YX=e-RP1wPN9qGxsom#&~Y@AJnKm1QP=PK@%RovQ8m^JQHl`^E}I zJ8yr(O!Dm4dpt3g^ID#wYnrH*L%X%}Yg+LLXXkjB`Ee7s-EFQfS7SVLHJ=@yy(Y!z ztZqNQyyIE9N9mZh&~1J1vR%|ah=G)67s-r+aIyF7h#|DKx0k#94W`QH>80e9B9glC z_(cb`t@N`p=2t6oto{04WanRNPrT3}y_X^cj4HPu8$c+bqp>@(u8HdUy3uSGZTy_N zf~uA-*>4~~(3`$)lBcCuR3L*8_v6|1skgMeJR!Wne{qLLerPDlNL&4b_XEOOz?sts zY4COR8g;Z%fs&a&uCHW(c2vXfvWu0a={&)KcSm4Pk2ci>q(*mOUVQ4kc64^rR=tzI zV&VLd>`K~Z#r{mD{mnrQkK)Df<-=*$;Om{{D?Bi}rjL!8; zz{}eYa<#UICwo+KR72)JdCF8BvA>F~4a{VdT(b zRaEQ%=fz)-x$n`qZt6x;*E@p+ZyUYMblBon(W>vZ^57ReeTYo9Q)HuC^O_`L&8*Zl zHzHk8+?w60A6a*Hui^AiA7;J;denn!`X157oN^bT4>YU8S2hbFEuNO00HwQHw!5?J znL}{yA{+Y-hAfAdOG;N06YVSoVetAfy|bRWfa@kvLBSVU&Uh0T%Bk=?yR(~!9<|9O zaC|I<9a33}&cI^arfexDT0#(VsugcS-Sa5)jS4G?-s%W4|LqkHBr*6}RUBTNQWM>8 z+Nq>K-NjkKe0~~<9F^A3H+MBnTvmQXpjK-IP)gx;v2z*kg!uSX+61do3iiHYZ6X9! zN}9=9|BP;vu&jXrNpkL6tq7H+&Q4NbP2jRM?Bgm+#dM2e?}l?ZfQ?k16(egNMNVhD zV&bp225UlwPP(4hB^_&qpTW*+2BK@escHww`I1w*$X~zEAh5&}C>ka>ZHM(7t90oG zxZlqhURZ=h=HnLIkkYxIk}uEQTr@9(E6|ymMaqCgmGL2Id`K1ssWhgZMl?Bc4ERGODil~5`*g!RkS54oc%)~e zo}I7oe3T%Fp1ygY@>R3?&--d7uu{1vwFsv8-b45jMP1%&Udrv7pq0(>0>Mes;R zg@WEy=V=Q+;U4&_nc|8ZeUZF5aL{ca;rxzcK~S8AZ1vy4QUiq1PdGjr^2`8s2&a(H zR`W++A8ReEPQAs5{ER5(%e!qh?UbR`Q{QN5t`DvR6C?B_tN6t}G>UXsO5K0V9?qGo zl8l~JxEI##ZfA7o)s`knU0w-E?{CI4&*|j*FF)TbiaQa9GJgFsnYOr?pICej|ql=EMOei360(kR?};rkGxE6$pL_wSA8*VM#|^a!Js z9C?j@3wRl(?-<*Xc^XTmYL0yOn!QtR_9>d$z=eVq)m9;FsHRtPBp!1V&Jd~}cKvE( zP#m$nAter_iX9+fNVw-BS;dY+IKqt?$W4UEX})31j3U3oz$3)> z?lT9arXMz%tNuX2g&XG(aq|AAq7N7x*E6Hu@+T?~gtez4%~m9-#(sNn&vA>U8XwsT zh3zM&-FDXeWj&|XD*8w4%XW8KscePs<>5Ou(=T4S@Bt%hDet9NUtk!Cg}IfK%4byH z70KkJz(sYxaVm36N(|i3mG2aOj$Wwjr0cz$F4_|8h@i;JZcK}Kz*Oc7e!m1*c3E0J z4x$`>XZ$C9cA$HrS)#&0Q*xLi=s+->**skSTM)~vuw@qG5jI`5b?m^}v$z)#2p?;R zcJqU94>d%<@3$X`H~;BuH|2M*>Xq7o|3W^Cffv=^;)$7F`^%H2t&*uh?znTRR)d%H zRuVq;6Z=~`EiF6@->+v+y}CC>)?fg(dNNfL`+}#;cFxHAZq>}#7R)~YbHoLzPi(fv zzr67#b;#N3Mi~@j+wYJvBmJ#)ivE_X^+`jO;pUc{Qf;&1(tPb?({yHfvNI$9%As;8 zfm&QbnW3le8!;=TvbgyB?ufe>(Or@+-xr{TuVG z>pa3`R^l@a)q-81<&kRl)6r7BUXgmi)Ylka-NuB(X1Dy%yyXv6V1;=^!g_0i0LGFG zpjSxPn!8W#ZGBfvdeiooODbHCvg*x5@{!dLxiTe0|NYZ9FQVm{h&@AnTt`Auw?_OnV{@gD1vS8v$Vz2r;ONC- z`u+b_f=iIo5dwz}d@m@Nn_H*TOjA8D$w;f6&6BE*A zW*suWVle$);Wjy2Cqn+231<=x%$2BmLbn!eVf`m?JMIHVmdNK97HaB$XC@locMQ$pz-iP47s56*l)fEOYW}qsdU1GEG*CWEE`2wj@nH_IRF&e{u5UcF$Sn zY`u3EZ~r5B*7Ykp-We{3*u4ZXJtUJl0669ejht~?&?toY1*#Q9pPcYA_slPMae3`{ z&eV+p#0pJNXli3iN6vN+OW)N5eWC1emk;~E{qOos6CJfIG`sqpNE6VK(9wYu#bZU@ zVDSk2{(3Vr>mX5PGg#dmEp)7(uqWVsW&gQsM!e!5Zan@$AEC+6{mk@-&klA@P0tph zIWb4+#s(z^tnp&s?SX!QsiD!51ekMD)c2Rg$$H+by?d4$aQt(kitczbMyq&OC5q$F zQFc^1el!C#+=Q{QpL7o!VjVK>MyAoQhI%t<{QBC;_4U_3e!{ zn-6(dmr0x&DVxTe^m~!F+kC!in~b|zRXA9)+@zE{mbL<{SLd=BBXtc%r_( zXBv(>-`1Ot$Lc-Sga+PUUz#u%&a=9qdM^AN1W;=RDLnj$}U z%AihYx!rV^G3CelQ5GebxW0-Ku_wn3lg#Xd|L|U zhjMQGUkjdBH@x|Gc8YH=Jq&=ehA^UK6E&H;L3hjVb%~Rl3%YhX7>&v1Ji-W+l%i63 zUA(!lIcfwys~kUB!MTT#Z^*>sqO(D17wp;xY{$obk5Pm~MEX1-f5X;$g$cfHnmLt3 zxmxQtW=FlXl>~#_#>O;b&W+}q&(q>MT2g$GhS(fLa)yGohl?S1Z+6p!$4#wNpQd;}eA=qvP#gXClj1EN<3qrr_(dVHBALy;F>832B=2Y#?`EhTndO4&>%&v8lM# zDFC>y(v2sX@o+f3vM9L6${h3Q_Z2P!|J7N+7MCh3*>x(*#|t?lXjwS93!mMaua8S_ z*&fVYuzM`L0t{jFgLad|>8?iUpb6EqQWCcrRliTred{PtYp{9m_*Wo!N?s!z0_bN; zQB50I2r%Ez|L{6z)00+rw67%#k?O6|-w#q|TYkNd6szHN+C+@-Rn6~>W74QS_;no6 zwt(gH?Kj7eQJ672Ev_dM8sFWV65)fVijJb7afizd%ISm;=No)oE4fiL1%I;Uj}yb@ zh!A;*xeDe|#LY*a;}muoR{v}hyT2-TzK$g4dcssa+~+jf`Z>^{?e-Z#atN@8)kjan zC|ID#{xKx!t-%~W(R||xARUCpu>p@mRsj}l1(apM6zf}3^5Ak^X5b&PvhsI*@789~@S)=hX?ZSr;fG+1H;voEj*!kq8+DDEg5s(u#ANh{DEI*eZ(xA2E2w)s!m z(%CDte0WZm)mE+t-D#v{=<+$Y&mIogX*u2c&% z`poV|fcAr^zeX|XyuQL&RMAJQ{+i9g-Wjf(-`prV8$UF)| z9<81&DZnwX!bq7hj%;m59K$YO?Tv@Wv?rbhnYET|);gCg_RQn3a_O+Zc2+dU1OmoO z6^UJ05T@y!}ijxcP*{OS7}@>1hmchbzm*y(z4;eHz7s4jR8FQ zJ2*Bby*g>qkMp3`Bu7d&mW&W3L7-y0;HT56gR#VyN|n`a^YkM^I?$eghXQC-0D=_d z#|wP^DLewiOiVkNUnChCK3|w~%zyjr?)a>Am$IzD_>(AUb{)Ttnsts5EJ!?K0Z&vc zs>8E(v9$d*U$>Q;WpYZeENNu3*CK+^H_Pn5buCnjA2D;iTug7T zLNZ|4Vk^zq%HFBtg-DU9J4r2Sl;9j*9@*|U?lpG){mWlrMcvbV_idgJC4ZKsTntK2 zMX3qr#vBuIm^T`c*T`z;oZ6@I>FyiL>IYbXVjMV2-$}?wFVkKn1T|mw>~V^um28k4 zZDDtEZJZ>B)?! znVKDW;peQq=jID$u_|#9@xPMv_c;D)-`Lu3F5G`16UoUfyzMMM@nA-n{QGaGG~f{0 zgU;yu;zI8N+26rT>1e<}pzAcEljb>ZvN2bTKa+*8f|hu^ZeJKPl`H{9mVs!2*x4U> zK@#k80)1KA{fo_Jt^dLs$CfEPn%(-Rs!FO#wjkosesLL7P5mumk8yTm;9%+WX!+h_ zEqsr789Ps8+L{K_3F06Vl?vwMHjC?7JtOffWnMsb1GPPLsUz|&DOwE8$n04E6Hvo2 z5J?`MDB_nXjG#A!`DO%mR~;wT;bCuER=yk`SD3#_+mo;Ev}`=>Gp+#f6FlFWL4xjr zUpJTfjX7cMaPY(P6ha>Efkt`gPoj7{ZF9TWhuPI%m{T{C6_mtbha(xH9Yfjl$P3j+ z9eiw`w25fJJUamB1Fqo>EdVHn=WZ~B!t-o+x_kQX<;}(gShiCzBwKc}VoBbF8TM}^ z!`^3Uh4{*3b^X-HD$k4@c7gBFHVv{$G~^~-8AwZ78R3M}dkAxTv~ zVJ^hfbbdIIPRTOUCwoDnto_<<^B;$!UI#l42z=LfcXKl{ktFavrUHStdBdNoMC-u1 zhmF6(2ybVE*9XIe!aoRcuVo_(st4WGSj~1Yx+8_7663)(kj^Vc<J2RMbbYka(z|3 z$J0jWJ@ZX^b`^)5z~BG5d2*0Rl6f*ftEoX!5E1|<@|*I`*+%p;$Y7hFtWq)7l8&c+ zU1XkJD}cyU21cXv!R1jY2TU7KlwMG2l!j9&3u(Nw$l*>2?D^d4lpY&su!mZN<##)y z=p4#+EYWO%g6;lvL>i^xzUD`B?iX~i3wa=$f%7>yOV(C{WXrZLJU`~g$~6+Vo`a}? zofE<@Abclb1V6ylRhwd&KM+-WzpzE2N=BvFXSUsEv^6I_u#cyaB0Mr&g*mR=Dmvo7 zzNrKSo2?jG1WotroRxIKmwcgeq1T-W{A4q~0*Ia_1;b+t%OdC2NP7Bm>lCnjz?Q6_ z091yZEA~y-om1W;j(U}rA0$WLE)pNH7VO+@wriSvGr#G!>-#R(0aKT`HkDAN(rN28 zgiIo2%+NO+lcNjU{!7;O?<*jyw_@IH-t*$Mo|b*fsjgDZoWLUa6bi|p-2C2NjVDVKW4jSDz9~^?N9sS63Qmkv9jW6O9*lfIpbv-H3E6ih>sFQ!mM#Wf7y`{nm zE0Bswqr}kBF%@`cX%1_wwZ--QG;Hz&om5M0OAMh6>ol+2b1r*~A{t5>H?Ll)#W7u7 zffzJ9Kff!(PPk)^G8R5dSu;+eFvRY6P+0k0LBB8|RGE^j#E+ol$Kbn^8 zkk!O2JfsLw9Oa@1wW{*jY6Iay|0cDQbF}B>?nuc=5}}3?ultEtTX7`u)aJ-PT|_$* z+}tMMTr&QQ&Y%8|+3Z+}Swh^du?j-QY8^KSU`kWcw2TFKcnGDYk|O{EwjF=(;9yj# zm_0M{HkQbks(+YeIXAYeFpJ|Z$;i|wR%!8ReNOc{`Y*oj6;5EITg^5k0pJ3Pka0&M zt%ZLfgzI%9v%BAp26$9aj-R)`2~ltKgz}S`2`gxWojV=rZS6L<5H}xR76ZZ3(yNm1 z?){paowFZWZ4vM9;Qs+;*QCKu(x5J(z3r8Zt4eSG5+)FJdV>3p#3KhVa%mo?^#gWi zhm^{a>Z9%bl{>7DP*jM*p=rA5Gp)SY=gUNR!zH$DCa^Oa<#?eLRlmkXO$I?GxNppt#iK1(>2NP3!K=9{7iCzgtC-YqnsK2DOY9 zwvh=rceAi{?e2*v`XU&}pQa4F>V2^Fu7a2g@3M^YJ%`Uc|NI!PY8-8dWm{XPpSXbm zMRM-hqZGrj#I_0qh&FO6vyrV*kU!$SH=Gmg(2#kpD^7#bZPKb6R@eA1;8Ml*STMgp z-mI!y`groB5J|Pn-J0CrNQ+hcnYthLakCTY{p|Pl6C8y!+|HF!ax*d@^FM3{EalQ1c3VtQ-#R$^#Z_#`rm63OU@^X zMCopM=>>ObF)pd$F^?f@hLx+1GH)N3Az*m8z0C~wvoR!1fz~+7;!y>2_Ew$ktM|Lp zu8w-gNDBA%C}`vsU)<0_VI`ZZdc9|?bt0j}s_|8gabz<2XN3YCy_xRLOD7pacKgnu z4oq|Le+-TNYOgD-dDr0jiWpbM%Ervs ztPhyM-@~b1&qz&5a;?y1y-A#lBEEVl$gho?e#JBUB4_v}+hQ`dg4wpE>Jwf({hjOW zf$PvJ%O?k!7GC@=7Q|joC%gR=eX0y+RfytBg)|MWBxRWE;F1cRwv&-)!_X ztC=TV*OvLS1jW#H;Si~q4-DPq!(FZ=^~XBD*X}-HdI)teOF>@tL3MmCoxbPNJvVpv z+KY7e%dQb2lGy+nth+gqzF}(vN2?J}lspj3uQNOBB9t-ajeKiOMLU3wQg_$jrCGX( z7Ee;Y;g=$dTuZ~k3*&gTK zITbb}B1@!-hD^3}!>jWuSUT+r{^(}Q;5ocAGg_$RH3^g=#agQZ2#W{%cDLQjxbCoz^%>v_;Uor$Ka*QU8#+aI=AYH|$zd!!lo$Z%tcE!&l_p1DUJ z>(DWvjgf>+?+pYVanr?WmYj5MjdAsu+%5{S*_t|MPiLR2tIzSZmzWY1^aM$c23`bn zRmO87jWeZnx!TR~aHV73`@+U}-VZ^4aHrjlWyYX3!R_?1N_cLO7Zf>cr zH3y=w905XAJK^SivI1*9_SaMiJx5@+Qgm<#MW<*;fk8WGlCjrTrSg>#wxv} z>X8Hy@ehG}-_~_BxRQGJNW$91*7!iM@xN7;tzCfi)EbJ!dW?yyj@|21^LdzQ{eKl| zS6zQe7})HwNnOt@proF4HDjB*+8rPz{l2<|>339V*1bA3*?*9dn48dVbMa%49ml>_ zE2fKX_xqA4L5MW;%k=Q=ybS4B3eFN=$*NZMIP018o6OpJCISjpV65NS8Y`hC2>B<& zVZZapcIOXF%>Gi}%7o2-Kd{#Eb)f&iVT9yE^Sd*y(EGkvXxVV!50&DO`g1Z=B-LZf zcPsv=sB>YMu`E4@Rhrc%gz{B`!12FI=n#1F?yZRiUx6jXLOJ3#Mxb^r9qyI$^K)}+ zOX|26_i+Qif7l?XrldT7^3rT$ch~uiyh1D#cHECv;C%L~ccUf!OpGdWtl8%#n4`UR z>UNKzu=rs~0?VNXxHX}lkG&nT$%tm4PvzF;1bT?R6ihRkWqeQtN4L4oXOu(_t|LXx$VO>OZtYF1=>N{E z%B?{~H3$zVsssi)QVexJ?kfhOV5!z=uZxr9*MFNC$2#Al-!@+_y$+d$oVO)Z$X45o ze1*&2qEG5rkN+KXypr43=$_r=${2W?OgB|M(|V83Y5^)=n3a0>rHfpcTUpsXJLp!O zoc_vwdPIp)csX&LBsrF1C~Q3>xt8|`=R>RIR5j+uHqg0+KCref+TP64WU$-+f#h{^ zlu>CpKn@BvCI*ka|EyP0#>7^#!Wf|oqZ<$fc%K;Z>Ss8un zTt17JN7)}8mC^(d8f!10sAIBvMud=1A%YUxe&T0^xVj0q;;#w?X_<~8?gv`&x@ZGu z4F?C96%)c0%pBa@(l1|<7||_Jlr|f!jmmPxTM*thPqN!$*Y3&3x)> zjorj1XGd1b`whE9Tr8AwK)a)v=nMYk;Q8+~ zb=Y-snq>niz&pn9`FB6n)E5@pk!HOvD07oKs*CHwhJO5cBOgNp-D9opwG`w_4Yx!a zdXsgJyc{}_=f3xwI=ZvIpkQ{n_{M+S29|ucg4X7LVczl%4)1(h6#mKjs5Cam(S)dW z&4bjdVZU_?=UzB|xb$>H#f$3yI8R!f(N6^wL$aCd(N-lheR4OfW<3bQ!{vZ{(iQ1_ ziHwu200McY&U;D`aYe5hr!M`2Uzd^)vC#cEk@|J~=fMa!+((j8G>`O@mmBwlcW@2A z$1bA_M5B>OJu{`dQJn9AW_>39oJxAXD_N~X`o%}jgl zH7Y2+tUOAq>FQfmR*#E_z}42#fwuue=%SmW7VG2t_SfT1(m@|x4^|SoR_w2x*y3Jz z>{uEs`J$8GN&PPoGB%vI|Fi(DxLjdmJS4y11p|>iHQU!mguBxM&xoHire!f)pB;Sr zP**a*^}EO=&2pngG|~1xv~b2+xd7M$;;Aw-G1H6eAfv&Fi7vpr{k-);lRkbzOB{J| zF+DLM#~8P`J#j0w3;Q6fzaUS8Awg^*D&B8AY^CXq9O-?1M5EiNU-dE(O2)G=X%nfT zH*-z?F!_1@+|RxijDJM!ZyrwZmNQ2$EU5hYMaMvNXrp;_`JUEJ|4NtpM`BvqRbHUv z!hp|Vo^`~fVmm2_>uk{+Pz*KWowP>2*?#|FuJ5|@JHN6>f2M79hmLi{NpoWpUh zrNz5uGVn2}1!_5{BEZKsJ_h~2*$hQ7f-35?SDG`EY#0>iU^A?GfJBA!5S373C}p6 z5r<-A{R}!z(HgA}Ez~HrUl>L;xY5{pSiqXC74NhdJDJtod)wKv_TImfsk|<>UU!X` zdeBMi_xF6;3TcG7+-%?o(w((&+Aec^sO4f3)A|l(-GR>=_oTOf6<+VxG^V6M1GD_6 zDabylD7ymHok)oOJ^38Y75iw-qUgSqnx{RFzzMvZpXa4OLqPWka-fw(ywHoU3wy$l zgthqYU;FbLjvp~=2P3r15lxx_&z-&$EdM3fAcO8R&U%|-kzAjVUwa+CW=#DgaeVK0 zS3*Z+s~x1~`JYcv5|3Lg{V$l&1kW3;m=b#Wx0u6pMF(OHt~r?mg*GV2q+)0!GnG+~ z=F4TsF;bFKmqDhJ%J2DT=E`;d3On#F^s-A^1~-B*uF#A}z$6T!ei{zDnMAi1pJXhB zFQYJx-{k>wiG8hZjrBA;PKHVW$+8Y!)NOlHuKt+M25>_ids3CwDSGwJ?}10`s8{;E zB-g@zV8&%+cD6r%BoD;7U?1)7QzY^%6Xf7%dG%5xkRjAOS-a&CYGKak+ZgMqTV#8& zt%v{4R875h1Mu?Gu-WRM_szCo=jHub>wx;eK> z1JgrhVbfseN$FX+4t^O@Z4M32te1LkG#`GNz0L)-np3GoGJFK$D#p+n6B8jyvOL8m zW0LuT(?r~(Gp@E#;ZO=^4!iad$)iYSvPMPM@3HSTb%>2PqI?jB0G%xSkZ+fMvA`Vp z@b@b*Q;^YotLD9rwSm#?l>)w$6 zXQfj*es(N@H2iVM=s}Oka1xGQTG}#JAS(UJyVYX-Ft7bTez}pOUutGK%Iak zIyxFl*({kZc@@Lck|SoeH9MZx@3eLlcRNgP1h19Ym3FRvuL*{@WB0?QqfH(vjs&;A zfoVjA_swGmYq>nM#MN+lr~?*SY;YEX$9@_~-_AGs$$n1K0NMwIXg zw)nJo97%)C=NoaAfgZUQ7QXfi@eN7Jg0XAh1jht-oOKhv++U}Tq`bRFA+lM?e*8lT zUwj<7M8CFRR+R0xoF+D<`_5@Kwi`Vi9lmc#9MjPA%uqR<5pE(a(|?mZxa5LAul>KC0gR5O_on63~ockVnQ>;M0fr|5Jes$KK(L4Eq9(*4>pmoFB zwBPaNdxP{bejrqF~u7$2FC355JNezKfmYgB9N zo&ItLEC4Dt)VuS&6g&E~H>&0-gsT15d%b#{LNon|cV){^#q$%}`PYnb*Zx@y2CvkQ zoeR1xXHQCRjx);NFS$)lCVM)sw%vt7mN7vwf=r;RhpoA#%95HjmRgNn@(BG+&s^k} z*-kDOz#0Z;{j{!`dCoZ6+7(L=!+tMGIxa;Woyt9dMRw`e?V+{OF9L*orjWjH*HFZn zMqwi-Yk%4I|Ezki?LVOf4ewdizrv$T-UHhuZdAuqEW~#OMk%xP)nr71a?eHJYTWt0 zH|t)z6(Mwsa09m;A-~fqjs_ZfNKo6+EZ2XuSn&g!m?a{V>Ms>^Exoty*4@cQQqtOL z^hdX_u~_)kmjazo1U+8Vz{;&*@na;JQSZIaJUGaD<7>WiUjhSM_B<}8=57TW0NI9W z6Askdgw5Mn4Omi}l?g1GVycf$dz5!465&yf_2lUUi{RXK&XfOp{)ejc>-gv>yaQq0 z1MHju(0r~p+h!^of*x9v`8DB>pf;oaR1tZY2|#>MYNH)A7MK8RzZwV4bgk~2rF(pK z3)2F_6U=ob>N9QC%@}_#`xB*?j^`BdFLL%+29z^CStkjc_q~mn7I>?a zx>H-?)(mhEpi2Pa54YN8M)%{h?@f4)b!JjQLDIJ?IRGt=GZ4!owN!O12VaYCDU`*R zA|ECaqLT?2=IgS?_N=T!JSxxt5apVy6J{AJkY!0n@Lp1A&1W$6r?bs)3bH`_gWo); z0GHj0r>f&sjD3?&bmy^Bs*g+uTRcL2#z~!pk~N`6;pNMVoMbnF*I^ups&8VmwOE{3 zquWDoetCx}MmX8Nc$`aT_I)kA{w!_o?1{}xQyOIaqNx1*W=*wln~e#2i+^ru+IxEP zd}?^gW5^z@1bWQ~4K6ioyU?u8xNEQ5&;l#-ANEswc;v!A(ml}=`}*tw=zqxPeUt}! zoupf4mMo1FuaHhAI@WH@T18r)saBTq_#xeQ?~r^!i8j~kXeSo`08^fN3u zZz>^vJ1$5<5x~NUgWSe${vt=S%8dtXnb+?6wf2EZQ(P zv{qkuivju*!2It|ir!|-x0k_a(NQluyU`z!mTaCh%P$H+}{FNVY9 z2-SH{^ar#f4y<~cr&Hl;-KMX7?pJtvMpv@+`>Y_Lb}UTNB&5(1g+c_%Dd-kjTKv(^ zTyA#fAc#VmF|PG-*eYH3Jj%R9V#5Qw70Wd`?95Q3U0$l~X{|wv@C;YFd-77r#*92%O~aeYeHtxJi~tivP|224;6AofDa+sFFDC`sA0J!_Jsr${ ztv8HQ!B$yIwxSwh{FYkd{Nff^pTKH>W_5jfbCq#edOa#;bhH}&_r#fl{{!f+B7o$m zz&QaZ->-O4e)RR0dOKijOQ5!q*Y0OeNwc7Vo4f0YK-Ky;; z@6tMQe*RJ8%9uS$QMxUflrR-yJg9rDc;#6WsMBSE%mMd9#HUa2n^#DG3QC7M*BJm= z$(^H`D&(CG0Zfz_+}zywk@UAn^_m*OVJF-tqTBJ~1*OgG1LMDS{;b#iYI*)qbF?Nj zE-fv%M0tj3#uY6!-tynsqCDHd=40D0wY0524LBa3sP0dd%ASs1~-ND}xw*8YS zcTf52`2tT|(!K$yqt~hW8p$20L}93~VP?9WNdchvrN}W6$mx@rzT?);%j_d1K6lZ% z#u8jlP!n=!=_f`s__61Z52#3NwSUYYl^sicS{Kw8G8+ z#fZ@rXXm4}DOiS>9^q4x3+KNPBH`kF27`u392>Y2Vq)HVngQ+s{_|A1fOC zw6e6Z0n-;_)z-rs-`E5*l9G&!jZxYlRqPGe{?xWJ@}>@c5k|_*cr1kjr6}{GB+Ol? zqCuaCA{UPt*v8Gr6P=Q_0%k{FGieOw-|u`)AFF&WM@<1~!B~;DB0PQ0Nx~BNQM4hw zy*Rh1bb7IiXYgI-WIk2VldeH^;lf#x0x}8gjKtdWzWwhyuzDUtRwrIvP5t=jcbN%j z9>G5vm0~;FTIW>AsF{#ch8P*)f;XTNB;AvcQe@B(4X^o9p=7 zOyG1G->Rc24n80YIXAQ$T(5X%YNpaArE)po3@^s{Sqh2gP4(7VYE&wyu`3?+O|E+J z#wrow27Xu!Ggx-WIKvU~^!!PP31@`+>7I+AHgRHbV}?6rnf48UR3(7Y*nBlwdf53K zZ)j{b!e|QA1;WHjzq?{Tg-2@K`MMR(k?-Z%XgHqJ;L>PQv$>Zi&--3|d4W7!afkCh z;%jQXZ2o@))_aI369pIh23YRF5A3&0mgEZ%A&(tcRHRLQBqqQ0zmN)b8abj_s3nvw~*8n^WR+uj0ruY zK^qm~N)4T$e}o!^I!U39wU-fg6~~+E26Ib@=-{mHU&P%xqTEH&%+%8 zr2L9g_+qWz9k%aDnDP*Z4GsVP*|`q-HA1gJOFNDSK7V|RK-} zkO~uuwrv(6=Ufihu9k0m9#cw(Gtqg^+V7NSWfnE&gRIIfFrr?~k?(-6WZ2 z5~0?TJG1MLd^JX+DPq1ENA#_+nIE^ljgy)iCim0b?Be2w>Z9-CuY}A0Ya{LR9P{v0 zDWi3@X>N!~=MxtsRGK&yN=iyvh)=OutZDj(sGf5qJoqKuA)-Yj$II(y?Eu}X7*E6O zSKXa;oT#3)uCF5=tI;wa7Rx)n8!buyRSvEYT1bjV@DpXh@F{&(|72%s&Bb2N_TutQ z(F>kn?O>7r%-+ufJb><1P>K%G?uLqaq<=u5i9aRcnIbs?!zq)Gx9>`^oL}QSn&!}z}f{riAAvgAsF+J~P|;fZgpLKh1VtjOD-I=I;&W=y5|q8IsFpd`{1 zw}pi@LPZ_Mu=ejlW%(80;qmnJgm=t;$ zW#x!VFD|EP7DLvSVC95XL^{8cEFNn2-Y9nSyyn^`^k}=p*gPe|FzJn*og7UD5Gg;u z++Gtio4daH`Y2XCn$mCQzI3hyYt8?~SMi~eAyr!>lQ`<#&{0lG9Nfpp{rKJO7}(N^ zP;^z98fNpomyPM%-{-$2PJRUI@rri~iH#&qe*gSc+hRB@*7dAOgqe15U zy;r9*9e}%(g;7+XHGAyQC*P?Mj5!Al=YmR0jQpmTw#bLvmJwCS4-}&Ax7yQNzkZ z^5Wv?ZevcEiIIq&3Xs>`c;Tb;r;7-gt*?7kGhjgi`diYKM^@1f`86}|QeyfoC2?_c zhn8&pJ$5Pw!}#^}+zlPy%(tZ7U0i*)4MhVS=1?jqT43l1`%8~pMuHF+v;bernX9G2 z?2VE)(YC%$FiRadafKS=Q;fSc5c0G&UP@0MNf_Ay$tv@|^Itt!VTZMX!%T5~echm1 z9Gp&LwtvJmG!kslo?+YtMGW)_CAhepDFfO6d_H2a#L>v5fd@b%E}X57f($QEP{-u!MwLvzFFCQguH&S*CKQ~75&IB4k{Ds>@950@T1eN2%Gcm{n$| zaM^o$D;b2+m7WY&J%FeG46V;8)iu`NBDvaR!f(oVRR{Y|b@nS#a&pLd352|yTgAoa zo`iuBfS0H+%A+V@+u)N*IMp}iSr@RDe|TfZMg^mgYahlQ7zHN5zKPspU!vN&K17qd zyROP|L#GN$OPxb^j@ULvjR>`8r)-!feCFaLbE9tWBcXAa-6TjT?;w?F70qL1 zV>|x6UMHK!l-f}JGwapB1KOfPnw%oVuZ<)_4;tfN&~~pJ>ehQONKuimfy#(9H)Nd? zIm{`8#Tlo{CvN=dck3Qv(bI_mpa2uADk=iR1dzzGc_Y_Sxa>SUeJ499w*h*uny!!M zsG|4(WW7`7z7cg2|JK*p$$x87?`uw|XTo4Q_+ctNkL?gGsWv8l<)Hu;t~fy%vkp58;Z#LZS{m%Ay;$`g zE&nOc-kzxkZz#%wontzC-D`nj`^73xx@X^C;7G>+Q%R82@`!E(rfI8vDHGo;2p8-~ z<>I@HD}9lO=jQt!e?ruZ6qJ|W*NWk{zvQob%&#rqZ1jJ4I`3$%`~UwdGZ9(YWF_AA z3>jq>qR8HRE1M8PcJ|8NWM^h3*@W!9$=;ja!}a-|-*wJ)&h^*jykGD4>-l_)`~7xL zV1T!+@v_k7-3o=%9~d0zO+;zwl|6cKBoyY&az!t$?htPB&%g?_N zAu|%3w1`}^UG!63a#dQ6t#aZU6RN04uqv@jCJI{Im)9*r&*YIa0E5-VK~7(I zM|Ukft;zkHy)E=r7i9@5@}!iMN3`;FlWdAnABb|!CYA2?JeYtIdPZZ!;YK2fAlgqs zeTANt&jbj}y_AsD*w-M<1qTNFtOiBcMd|SJFoF-8Gz~aqpf-eep<$uo7~!Vl4~Fw_ zaPSEJK3Jsdk(1M%kS;p<2S?mjA-CZ^(yxM!{(ASyB*3LMIe!=BnQMC(^PS0S4+B_6 zdT;?ItWuBI2GM8#UqOV8DkVBxxv3_hNQo0VOSulda)_9~0GQq)_#dccZVwKUOuMdY zc^s8LfS}HAj4LQwg)3;pU6lxwVhh~KIWrhDi6p~}2Qy+cewvC?ek2QOXR)(iVl~qV+Nf}`q#q8!KamGg92B}Hdn#Lo|iAdjpIR5!pok2 zrS?Zt2|g4TS0qCU+uO;4JSAE(zM=&a5x0j51CF=VKwR?jwY>g^zuWc)NHOb$_>9GO z_LKc*9kko~x{%jPRfCI)SfL{WEY{UX8CeZ@B*4T9lNL!y$q(7B$igrsm-ZHQdKE^+ zKQTV89)7tTJ$dfx)?5ihQhN#fXFF$|5wfMKi+j<`nsxR8U9qej&WB8pmPjt>a=Qil zDCru@b=yd#M7kL@+9@!9i(`Vq2_^MwhhdDy!T+pjpFYyc4hkV;2I|WY$FHM*Ec@zg zO*q9#QPrn_s`BQRf&|*-ftA-Gclbw_j39Ay7Kv`+JE99g5GbLH{W3tjJe@It7}M9+ zl-sz9y9(2r`W?iuDJe6k&L?U->&kffR`IFKr$aNn5x|v9|x+914YFO0D=zoWq z87nVKugU(r8(ZtHC`Jn|pK`*R!&=_D}!3(&`u99jpg&uJ|4TN!bbrZ~C2~M^sB; z*C#q9Rujg@4czM=ss5EnMHkzNk6^<0!J3;aXrrZ-1dun_0BPOADAufjq$_3^+%_C~ zp>NceWjYCC8L)aDB6HJ&sPVs(LWSlL-n+(1ZZS^TX~LbX;Kj0VyW5 zn~JwW>n!-;E8kTOp5C$s*`c!`Km{E^(7BHXPZ0)kmBVkPy7+j#v&{*y2FP^@6qS8t zd3%<;#9*J_+aKBXIJOh;B3xq4Ek_MFF@sEM%LyaBLuQ!IYBYsmhq`YFDuX*+|Az=Q z{7BnWiC7OVTA#U1cirKHJ`HN)(NTV2m4GP%k?G;N=f4=fBc#%-$XL{)GCVav+{2e z6l}^Bk7fHqXZjLzQ5B1HB?8}@wD0L@d4T=IcD;i}733c<#)OjdrtxNq2YvTDE88!8 zGtNF#5GG8R5aruV4Mtm-ETm;+`GO%$7a8=@gq|jtG#Dk>wjqUsY=a6PZYc)q-+d?B zmCk_}jQnU4N}QW88#NN6V4dGugz~6IJ$>V!e73hVf$oj0LENI1w3(517FPCUc=NomdQarC`{jRR6I6}ax zSuJf)7JgL8YujaMU|;}nRxq>Bbu1^&oYCl9{xk4+>F)mav&3k|zjLuRc5<(VHUUyU z-}H9a@dFf#8U&+RN~%zckk?jzc&k z0TBzFprGm7Z4T#qd~k4(DvbvZbn!u-P>a`df6%CX!%bryc4U>o1D>63&%Yr6wy>|& zQnumW!K@U`;OIK)7CYmdkuXAeY3kUE?QM}qQ$jPR%2empOh=HAh**w}xxM?KqSK~% z1kK$jzssW1ic9PJYB2K$>*&sZQJm@r8z~ z-1K@KT)1vLnoLXF3Tr>9;7}WLhCVOnQ*;x297qG1jj1_562)n}Kqd|&706lJYP>dX zI4oo<^|)k0Y3B0${@~X0kt%vT4$yB)=WxYkFD-`>_B%vZRvN=0{u{=h*=A?18J4_V z`N{=Mq$o`th5M?~ZK3Hf=e`@`=3~S?$X%+n+{Bj^A(JeS+s zKeJ)=8JBl28!H+bP1mpT2+PXKml+?LySlkDlA*y_1K1UA(nG;fIyHu|(a%T_W?1s< z9P|$b_Vq-!E#p_fv$Sq0@1}&E;QgH3nl(X>7#S8nPC>2np87Tajrn{sUNP{$M{jtAhof0&gb)W{tr7+noJw_F$5UO2ZN!wf?2-?0XzU z79|c^4*+U9i;-GDOsFUtNhmvLXm1#m7M>RPwQN?&b#ok}(rWK~<^)Y^N^3NxHJTaO zG~wS_pOXAZjL{Qs^O3}CN`u!n`wUA4ZK2^QNm&p;1`9So@S0gz85z4KT%zCGnY_!U zU_aqj{Am2A0sH_TUH*EftT^hqipxAPQJu!!K77E;9i`n$5Hb4c*4;2XB%(4dU&1jAvSuoLZ0b#Yc7W^rY z=J({MMGq!#UB$0o=_VV{I#@D@{lwA~Y~$`LOAK)*M94@=NyW!~{kE5wr^CuA7rC}( zX5FyHK~5XkgwjTG#;c>hwYyB&Abw#EWjJpVPjV( zmJLXk<|e%{kB@XKrYf|<5Rkn_)9Yq*D3>@4#+sf#e=z23KZCLjbj%qU$X#WBxI;k4 zERe(y+lAU`anfX%ww~Oz#7KbIa58SNS!ZHmXde}IR~NWuZz3ZX_goNNdz);Kwe#G~ zO%O=Ww*6gS~@bi6apw7?{Q40KGrDyktp;;)U);rNf_t7kvgE-CeCrxDq$ zuQB-)AL~D7dho$cCop{#G)5vx@}5)NJw9FKWB(BrQfzHey47QNGV=f7qu5JFN0^He)b@Up3-IU{#9$^iH`Gpz@zHR$_ba%G=KOP zy~cSL!VE77z2!}2@fDR>*pYgp`-$*V(H{MU2Q|hH1WOZT9V(d0?aoU~k5vSfgCjmb z{32rEb=lv19bng)^d;FH&{|n(Qj!=~@~gAD z$4;s%*Id+&+r*lijk|)<=WUnScp2h%TiZ=E_sqp|)$01{FVYEL7D?t#Q)Tg#^^1AO ztUGoT=0k|r61~x>`pc|(s_zb#2|X&K+r~l2lx+qQNF|B6*|g`vZi}UKV%c5DF0eP! z8UaFqaLd!<$>%A|7{c!lau>oD%)dgxdU<&njGc2jZ!^^gF{clpKTK-GJ+YMyFJTmY zAFM>rs$JI&E|km55$T+yPp4a3(UYFnS~rn&`uh42&;3Kw@;Pq~w2TZNYn7J&sBCbD z&q?kOxL-zPn|W-=IJCb5t>(h-kel3ZP*Q@Leuactz3E^vGox+L0bQ0b2qx?BYq}X2 z^70Ohj!H8U+{p2+4)YpDp24l(my`kZQ%;V5Nn+%(gP%;qr;rc?^XJMQK*~=tpq6gg zDQ{oDFt)!piiWLU;FYgO{47t26jGNwMN<0M{+kVgmH+W=m@A()z&5hItWJRc{evJ0 zFlNXJQA#N*^NpBJ+ECo{org^reh|-izo{&S@6Trj29Zh9bf{W5cczgx<&4GH@Rb$g zKn%5WBX$~R#?mIUS8z*B2{el@83|s#q^^ zVU4t!u*zkuxm)wQrqskI8H{Nx7nFeXk^U8*@WSq7hXWud zKrz9GkaYc?1nr0pG$8GO^SejqqSfiLJqe_CWdJgOFFnTS6v+Ur72DkVNd7DO+m~G{ z`@i%#tZSBt!1ZHhX-OCT;?y{l@L|38EW1QyPhjXhCFLwlR$y5&+{_;<-^Lh0UTR#A zF$pnou4x<2ZTeQ!>hjU|9SZCnDdLJN@x>S&PuK4k?d$icReYQnWbJ)ABbF2% z!YDxP0wM~~G{TW`5p;ER(Rw2Sz7vrZ#}WZZMt zkKt7v0O*R%@YMYXt9Wi@Y~sN?cZ*&Zpl_-dD9J<+r^F#mWEYgGJ#=C(&=0S8Uw}bLdoy(?7Pe>obu1huTzQATR>JGnl^QP@<))BKAbC z`>v5a&vLE>VXW-yE3hTp3%2Wo#7N80l9)mbKF~YKGiIL7c5usqf_SXV2pM+36f;j^_FDP3X}3d=Jb;u7HtYXZqAI?B2W9jVx1(>@SZ=Amx)dyA z>EH#;vLpuA`dOCI_83M@S_z2sGL)Ex{w}~7V>W?>gI$_k90s)8k3=eDS<-mEACh4P z`EK>{_yNn^Vb|VefdTWUktlT`bl}wj4#)Y{kFbUYNUtR2CG&d+Khll%Jwzq!z?=JX zu*k?fx3b=qR{K}y{x^eF zR=KPY#j%@?aBE zIUY3bpjy{25h-bzKoS}h;?$pMUhoIf|9Y%F;X^Go#Z#l8$cg`{<{nRe98K}R2XQ}f zr(`VO56}M54WD|zphzDM`M1&V%s_vC^C^8}br_Q5@dLz{PY<1+nH3W_Eo93HInTHQ z_xSOT+eV56aI8bC#iu}E*?IGBgxY*qkV!~*t=u5dcp;}q0CXMdTCMo~?IZ}a0laft zC{!a4(a_Ol7$QL`eE*(c2u6ot1jH`4T0D5Q4{4sgQTFrq@96F2e8M4S z@Emzg0pmX7;`@W+3b2N2d~`f?sGC-1@@rqX7ncgkr-4y-B>bYq~u z*mb^W?&#=HfthhxEMSI!GL^z$i=s>X8z={mgIlVIi=q)h_b^EwE?A4Vh406mkVTuB zHJ<#G=^)e&B>Y~*7zk=~YsVOPH z^ii|xFqD8JBKpRsG1_E--d0n{@?0~P!>Ws7XA@I*F`mUWr-f<{z~sQ<z9LlP&?{5OVX|jvfjytoj2-^#E-o2O8XRMw{cp z_b5N4+UbeimC7PrZo7>Z+vz9Q%l2hNa_G|Gh|X~ZOFDwKEpid9_oLOvSq#(qDJ)k~HKp6M z+s9=uAIceG-#c0vv!j2-pJ}&$w0Tgd9kMCkyS+8N`90!Cq{Sb0f+pLEHlHj_nFwGb zz-Xy|tY3_gT#`Tn4g(TW(uZSlvreAJc0y;XPcvV4ppMeajqG_lZN49ooy})!2dFGA|v}W%(_TOp+k!d^D+>BowhXd|@?;1gMi( zS&-ek+ilnPetA+2Z`Zj=OM`AzS|i>@=}E5dGrgmYu~v}lffq@nr@`ILW$o|*3Gu2_ z%B=dG=OnLw{WJyPvH4^O^J#E`~K0k zh$xt7ZXYlm6_Do2$;$8T_~7jQf+(oYUU|c@Q=zW+qkbQRVHFgY-2p(c%U(u$f@Xq+ zMKmYcPDQ82uP(1}m)%HYerlS@5u_Tbf2CsCIXk6MF?sP#yCTA2o$t?|KTR-xy_p$B ztY_iZc{Iz{$}+%s7rDxEMm|k}8n_@nPOyw7C4Dx?{np-Ifmhbg@Aqh>6_4lf_7yLH z%q1g!C6G8b-bu8Y_@>$~?{tir?6##0_fJNK!RPe$T8H(o65jvB_o6!KVOA(gLuq1U z@`zVg;E9MPzf&lzkfbBT!9Hwm9tf8atO)=Uew4C1YiBdTTb9n>1M!!j^YRADB9x%; zo=PbaKs}4$+X9@Kgv11X+nrP#p?@rR_FBhk2svd%WUkKs;(F1=@msxY*3KRyHr z2OyqZKn^btxQsq~H~L?xMYy;St4pLvU{a)AU+d%|sc{pAvHAujRP&>~`pBUTrgth* zWq$roklu#`d|GJDFvIY85T|wPwxLYACeyp!pDx<&o66cBmgvQ0Xh;LR0V#vhm-*-3 zNzkZ+$_J?JL%_XC;j{??%NOMmou{0{o0X;t!VwmH!u` z_?wQfYw4fsJRo{0h+mOSj^*GE(v_eh zs-hV5A9BjdOg6=zY`>>#i2s&JJ1+0iQikA5kSNqW%0HICMd|btd&$(A9YO}-nsHmD zaIkhRmGuStw%maAz(bbaI+SjCa12=j|wb_7mZEEYK`vVOnZv(Sxrd74|b~DCwL^j z+@!yP9aI7zmI`q8P8M(=pl-3{gya-;BxDJZEAkLm0Ap3*HqnxoZIl1wA7M^pmqiBA%PeCr2J9EJ~IWrud31? z;10om^r~#vj|~29A?~SbfwW~}X}{vM`>~eCS$PTvw~*}f^yW>P^4n9Uz1?beXo%46 zCN~CC^Ea2K(|I8+EZ_s>Wbd@kBecR|7%!+zk%v(2Ex*IRsF@0A6ZJrcvaW&mA+E5t z?kzTF{-Ygrjp-p1##^axUoKir@aEq(X+sEP@bWq47JX3@H6-1*osm{-OTCMG>B>yQ z8{x)UFJp6kb?IT6qd@D%5@+ji)=d%-5^__Y)>8kuS0Xh{6x0gF*+*cSqanX%5JY1x z)Vk4xS`tVt&1$#!-NWb2+ej3D7N!KE6)DU*kF@q7+4zbA*D>1`Nm4RW*s?Be)YxGi z9MdAbpLKmwv{s}bk|;644f8s&t%iNp@riK-?vOYOdFQ!#3BHHgyLLMbXNx9Um8RGc zbXP9~`h{7K7|HLIJ6ciATwnFcptx3avV-41G8S$?2gTW{TyBgLdjvz?+!Pi5%(YP2?os~6V2oPPqI*}naBs_(V7MndVn zcwczG-9+_=IZxJmk`}AJVF!v9c8L0ezx)xptMHb!S@lxS6S3aqg!0p%7eB0aZq zVL%GQYK%33HQC>u#nj~sPFgiqS}};7Wi=mkl>mD>@e)7A7kuvoc9o~YtmxPn87r4` z!T<>sfd6Q;+yp0H7ELXN=^GwX+_$DaCFP~2xt4D_KVqO0QW@k%AFZ<%v$_4mX^R~E zgp6guFLMj$5ktqVZPKKbMelS_!}0q)atf1F*gv8LzeFMP04 z`~LlVDibDX#bidTG;vYD;BljttEq{17U~60jJqV4bEE6Ez1#xqg??oy4u8{@Lr_ZH zi^>&Ogs>o*Id;eyx{-o|A^LdwtA-|upjI(D`4F-MC9M)7Mw%f~=xEfy686Qah-J^1 z5xoZ}(#eiJf>m4P^hlN2W*w@C$}JeziKr)!{r|%vRab2|u4rB7kVXRJwK?)BFpG!; z`M5NAM2NBO-P;={E57NESjRRH0nRk3EI)D14(xALS`8TnEu-<51`d^6HbbKiv(UBm z%_Rs?p{tsDe;14lqv_JqAwoNq|G|-PBdvw}ABfD!?NRyi|42~Gqx|Eup=#_Hqo3Af zkaA8Q<~euwdqveg%zlBB`#!|I6wxK}oKu0d#ojSy!VTXL?^TJ22OF|EJ`L}CQCtzo zZ7$OKF!QuEcP zv4H_^qlDaD$-r`j1mQqx33r7>v!LFPMd!^A$!ThlCHil;Ax27_BN)#_K52PA>*eQL zVh&4B7e9yy3U*Z%YMgG+hW!EgWjey3Mt-!KMptX(zNHs_j{IKObqCeXisw;r&Ec@s z6;Ht@-;}RCl~%5`}rLeDV z?u6*GhHCWmpS$aS)hN(%BN1JE><=2+S4WBA%90>LIilikdgXD%<+wR5#}xl;@NZz# zXeX|8KU?vbhlVRI7B23aw=r>ut~GHkxkxFIeG=j0cqz4dW9-0ez3RxMaskBKZ$zNV z_@N2W0*$oYW#4eJp6;Q&f-4u#PpalL+W(4gs`!bM3=CK5$j&CsP82+}lFj*4>K&(LEqwValtFY?8 z>ZhQADn92vISENxMV7D9z}oOSG{%L6J?PlU6rxPg`hY0vdtWg2VOIDc7PvZ_|Ay$^ z*6Bb1kPTFr0g*;Eb!`omQdm=&<`R6Y_`UeR<<(tbI1AJ>PGg2@`rgB z0?tBWvjiuPMp+9f!rHd`mflN&=RlsV&-OpvQq)IUq!xCeca@ls6OOS5GcAlBgozvxU#{KG zrx}d0JkSvVrS61HW6##q&4~*WDv(i0f-2r>b8|J}#t>sJ$^Um8di6j38Q(O@{g##T z)9aQc6#1W>GFDohFY%~FeEG{B^EH*fE-{^AzFXRBgpHt@_l<5#ZN;aS`wYg};q*=e z;V9x_;`Wa$n@7Gor?%Z&)f5dU1U3P15_$=l6(&yt=jI+}XJNp}kW<3bQv_sk%Um#df{Xl@0SEj79MNqcE8Dl_ zCR%S}YP~q!$J_GNi8gDj3?1G#ovP5`7-RWlp^m^_c|_NIdpPZX2LTRFq%6Z&t;3CE zIR~y*@VnBHXJ^%bQGldZr&_eyyh7W8a}VpPEIzoHqkJ-GaVgkk*#*u6sPZ4m;K3Jz zk^YhNB|ATV*N^kQ63<-m=R&{1xcVCw__*`|Ud>`{p`rxt=P&xPYw%ER$>1_3GWhBT zfRw&Qvj}MhLYIyvp9lyF+}H}gBmDf^+E?r@>Kl)h!J~ODlSL}RW7+@VqaidDzki2V zoUXk}S%IjKC5V2-xu`spWmq5+3{011NR)`76BwW1(6ab6JUkruI+8Ka<9iz@qE}Ak zP}Tb2QiZ-RwiqIJ^u0ma0;7`nt@bznL!_;$02{hT&t^)xx|T1 zQ(mKn=}S|fQuu60>AD=*hY*sfSeEk<|E*%3_vPfj3UB5ViR}Ku2faU>(NA0tOeNa7 zU$364GmpNnk%cR;@ld0&737~3o>>Z?0URLcqU+~1=jh>*B&c1f@*LrZO)ls$xl5Nn zz%*7Ff(XRI#<}qyY;B>5%^s``eid{Ib%%9F2^=T9Hq)|jd6ueno258T6t@&%907ga z?p_BE%`5M=Of%A(TsO*~n|=MN_d}ajaJlq-fm#~Gnk=xy3KtItIcpy?dg!1?xbdJL zwq@fI5eRhv$bVCg>6fB-udi>$8h+&@M}My zC1Srh&6hIzpfgkAlrb@Rlwn|yoBu+H@;IgNSsGHM9B}qw3kgZBjZ;qnRg2XPI-`}| zlp8@nmE(qPo8Y$X#;-fJDPyjd;Y+{k{?__M7pEXgCL8C&sxrAqhh1&5i+BrM$f48GlU)_Qb5><07(f{=ocmC4tUkBb_CoEqq_??Y|*S5l7}Vf$Kw}P6Oi%;K?)GqzI<`IUw1L^ zlKXf1q{n*U0Z5GjO1m+}MK1gyZo`sD=Ifxa%ayx4X>ErkYa8hPYqpc!R4dF0dstZD z;DRIPqh8#tbuV1njEvm;pHvr4ja@5^wp2Yma>C_@9jKxeS7Ht&`LQEat`1a7Ws6+2 zwMCIHvZS+K*TIs?V@*27NK#U24Lmpy)Uv1UZal1Qph$$w$0E&|*AH{Gnd}HI;^|~yn18d42j&d=+}xa=ef{{b zC^c!wnYK(|dTLGHKRDVFAHBx*NPf^(0vae#oQu(f>+Uc204iZ1*nda<{9F4tA4mG|Id1-sn#3UkCdBWpoX92=eB<3=*S#-2wQ76 zECb`)RonG$L+9?N6p-Bdjz%u z^uN8`-F3n|JPuYazi+096FErax1ze1A_0g)=1sl&kp&|?u}0Wrh)u>$w@uH_vN3w* zmY_D#@T9H?dT^%8<`pG-0vR<$6X1f_%A)83-j}ww0(^04NX2EjW`!Ng2O3Ts-TzTV z-hNw!LG~oNRKF3{sp~G{ar*_*8>wBO0IZ_96 z@e`jIWN)E=GRcH&tm!-=@eR{km5(c3~>kY{dSBLN}1n@%k{w3PnC`*P5b#(OPW;v|#^Y!By z@D~;~CaS_#w4J>a7{!H1FGWX$DQ~{`2EQ5}OMe2!;LUi_ z&(B|x5LIsEtHo2NG~~!^>Aa|%`if|HsKC-)DeHo7-FJ0?FP) zmF3vp5YW;PWa1t#Ze+f7U}L!6R$x5HOlM3)ny?z*8GD%XLp*iBy?W2hW-@`x|10wY zXUjDmAFP8rIOPcMO5XleA!=CV&Pb2G(w{rmk|@Ob0K&xB;y<;~9lk zV7fxwe@^zg(_xJp(;#$NE=@MgYv2Fz*Y8b|*)%{E#g(^g+*!ntsS;Cy?NcyPRC?WX z3*xtvJ%zo?leO++V3vIYXaRWikHaW3e&n=qI1)%85aGtldivQ4dY`pJJ8IKn$fl^VmGT}JTLj8@rD z+0-2pc~f^YKVUr+{^qa&yO9rT0gs$Prm4Ww}alj9f=V~ z=}@Uy>fJeiQ^yzgvctz=|2*_x@MKnzU?7msifXLFpM$U-D$zGgL@PYyCik!-U#J7@doGq z^rO)!^*K^DjQv`1A9`z>`?HtY%F2*2#t*pRS0b0+DFVcyGkXg&s-xnZ?Ch(tz2M_p z$$w@Pf=h3Jb4XDyvP?i_Jp=EnjSKA&`JX%1MAUDQvQu;Iw+`(P0cHsv2cM6Vr!oJO z$$A^{ON5(AbDtn5nkB$opcL*RO7PVU7i&my6J@BfasfP@k>G=|(c!Hybd%i3UUvfmFe^i2B_}+BARlZ8 z5T(>eXSC44pXY>V>1A{f{m_-x;xA*uSu{dI*dSgp&9(Yn+vfE*k9zcHAaHKEJf7KZ zi$FOP5!+et%A#h>AKrDDacdJ+!Lvt5nLn9U`DD4UiazsUUryWoQ29q*o=k~VB8Z(Y zS~=Oz4yVfOsiEr>$RO zb}KLq*DF=U4G)m)y0l0PMN`t4YA_N>{b zZ>42;b0W=*6aZe{SUySZ3LH_ElkUwFDf!+npGs3cSrkyI*Is#D{Q9A-6fq}v*JX!~Pos#Zae{2oH1^tR&2`TpbzRNr3RQeat8yaA z4SW;iqYmED^LV~cVOERrrIX=z+#rTEobU3oF^h;uN(9}Vo}M005P6&m$5RNqQ|nc9 zQC179g|M;^?R$=HhR&>FDvnqmP#`<}%N*Txm0Im)^l#e_sl8`kOXi5K82Dq(xLVVB zrx~5&{V$9-1Q8>elUDtZgq)- zSq(+oQrvjABouclD!pZ#(^px4r89ajxY+vr`4ldm`Qmi#Z@#@D3u(wRMS@>+ckcao z%2Fe9?D;BR@zt+8Na>}-LaYxG)YU~F<*(L8wh!{4$~kFr%Yoa95NW61zjz@=!$hm4 zM&fDol+%+pv2tI7^;VS(lnp{-uSomsMt>YrXUqMdAZY!$ROXbplHs4+Lv(lVy8 zv@c8>z2uZwDj&HLY5!A=-D)sUBT7@i@IlAYHlXQq!t?j0tq?ShZU8T09p!e@$dnhlBxw=oaDgrI6E#y(dCBNU& z(nE%>q_}wbFOUrb$`1l%)K~>hSkjchwZDO2k)XqCc0Zo-|Mm?5^Uph8qNx+p7QX|; zm6d<#-|i{%#eB3R}A@YdtO_B3!ylzgq@A!UEWBpx;@8YuF9Zf z&SoZ)xa7RS2hWvbv&Y92kc_SRNs8){72?HNR}aCJtRL}7l{=yPc&(>?a-vkRk&Qpp z2Tm;@!F|qqlf$5_kU;HxadDMSJzhi&(m3R!eI-S&JLg={BN4b>5Oq|!dGlGW? zUXnDuZqX9z%gA2luH2psuw}&%`@4DZlMfBnRGRM8(RkS|uVww1Uh0zE(>eM1z!pj!y}!ANNodP| ztw^p(bZib!b%{{;$?u8dZwk1Q@-rgIcG4M5TAQcmy_@AbQnWBLTXXc5o#Ms&RVYaF zH6gCxcw*g>$ee%qEfus`ZMy*Blz8_}Y`#_t!BMM@Y$1?iPCZn5w%3?Ze)n11>Bfh9 z2Q=sl>v=0rx2$m{-H!`TcEcJ&Vq#+CFS`f4^oZl+82FQVGb0Ax?2l}1rPwn?QkD%o z*TQ*vfVgt5XsvbMoF5+e8J?URr3*nm)KaA&Mf7Fdf zC?Q6T`!Ssn{%MMO{N~T}^t8m|0hQc-TjFq4ZjJy8TpvB5omrna4g)kz)(7eRrsG3Z zr6y7Dj7UQy;l;8AJm9PbFkUI^wuN&8e%G$G%e=yW{V%^NC!ioJ3sp^taP$i8N-l&s9nRDM7mID1qK{wK|B>YEsO>==0vcFNq&Hcd+QomoKY+RX>s_<1_E~{aGp0*Rp+VaIo6%e9$k&0oAO0=-<5P zu-`FMc?_Xv76LAO`BHg{-MP<5QeGxeCy97c0(;7bP6iJBgs!D@=j68Jr*7JsrTVR! z%F10G2vJeIvO5Db1ei}PcoV5I%>*C@Ku&o`+~U50JdzbL@fw}lz_sL{d9j9wea>49 za{t3b-iJ=3>{y+>lCpgU1KhUUA>hR&f9gtLF;dt9aIna%ZqR9zs3LNUiu@)v{l+Z) zrmWjO-N9E-QGslz@jNY21d$Ix5PkMOeKD-Bb4+E!Y+f98lht`53T5Ojqiq$fQL5^}wTpm3Lc=&fk&iWVb*tJ^lo6 ziGn0Esv)z49iG48IgSB_Tw{*?PXnwllI6cPyXKjLyqxT(iuI#0PS(h)%zRmt7D{f1< zI`DMf>qu!{Kh(BO8_?4CwAq$22)F{7`8(+R40dLlJ4#}Uu*d>JNp)h z&*AI}c_!uOlNOGQK4KcHee`y1Jj9+sdhNaAKsaMU_S~Ussd*160U?q8-_?Fo3yT&n zWb_j2OV_XbE_m>`L?^p#SO28Nd0ZY63mIa_GQ1h!IKMb`?rVq9%*|E3<5~}W?jJmJ zse(TAps`O1{I`+f_-rV%U!{cB)zvK?Sy))SgBSdJWI%d82ATnJ3>OAywb?N5-i39d ztPqZZQeC_?&9~Lw_9g&3D_*ULIK>CMzKOB9u$CKyG8Bvu?C>&l*X~L#-XlW`NymMW zYd{hoALqW`!|%F5{6SbJhjV)?qIys{!@(&jxHH^CMwt*MIY_oUvx?n`P6h)?_Otgh zw*F>x(TYypPndqp`7|$G ze!@Kznu%xFZN#;Vv4$4x8t$#A#mO4+8o%fbApZ46BL|F+`c=9wF=vE$gRUALWWx`oiG!FyXk$Pk&=^3?6>gKRSQ9jrF7h)l!R z@8PnAxeDCF3U+7QO3HGs1)sddP@X@WbXiG?<21rFH#dhDgxz|QpFc_7mfRl(Wyt9F zW;d&5jyxIrF=-(AHvEDw>gNNT1S>WXt}!_RMu-x*Q#>UhCpt4iwZ(^rL#q z()OLmio>o1yEsj)LLSv$FFp!es9k5!T^p!4*|hQW>Xx-BZuzF-&v;lb@HYh|mv5H; zo>W+j!N0$PxIr@Q?Y2j&YYsBZ8^7G2n*O2gPUK@76H-@kw{LCd*IuoWs2$IYq|Wes z&9o~+!52&zokxEKV2b*B3efg@r!$s}S(0{@fh{pNH<$lx&Y#L-Vr74mnoITCCu$G> z{Xu|l%bYX7%0$eR!UQ5y@0Cks@V)*gp39ddOD~hx5w%7Tkh!9O@Pi^Ub}*g}oxZg- z&U3wx_^CMokcibUJwR*p2+xP`Q;Qx5qR`vIsDM`g^2p#d0cwjsP8*bOpY`s%X_Kal zu&>Ex#00ld3#@-37mT?(CD9Xz6^$APek+l%|@r%lLh$3>iNj;JyIEQ zjlL(RX!@_jOOQYh>_9OlKq%IrBTHx`(9lQZ1l&4G7 zS;Eq5<`Q z4_tmwr33lsZ2?bB=b>x80wE!y?I%<+bYn+;xCB4 zDTZ3itbIEem_7T_-*T*Q0Vp(@l=P@?b+(o#jjoU0-3`C4q0jSz?fRjA%M)URT4D&` ze~V{fj6FdOGa&<(w|w*q?sOES3&)7!mpFn(3cSU=uz-aJq!yRkR-dqv5wehx>D|2> zzPq#v-SSHum1v)jJh?}j%uOa;YOUvGWe=bnjJV7`7VuU%YRPHVsN;@;0I6LX0V}22 zEQ`{kJi}MCS$pI84_GB8AIIolxmEI(s>D00DF~yd2XFx*b)aBdN(Uz!xOuZy-@~0= zE-o(hQ4t(wRXo277|iGJ+=FM@MZ5TE1osVs^heBS&y{@*zhg>Wj|Gf-ipg2|;cE7} zV3c~vjU`L@h};K4Q88^_p-Jq3WyBmU&C*dr7KEM5k8#5}h})^;C9mJs9wS}|;0n?lril8Hx2 ztH&zoh4kA*a#@U^q0##@k|*H#iNWb>qkyrNM@~PaSI%?ANr$c$Y6fcP=^`nfXFOt< z?0-2zsDsbsfU=F{R+MhP$x9)iYpGvz0 zVU5z>wa>d`-ClogSD7@4j^}OkYdfl~=}+XG=_kY118(Z>o|viaACI5)e6LS${>fmb znWD^xOQ8e-GwAOc;5}EfS_?7_3in6^AY2g+SM*S|`q;Rd;4l>3iyi_tVqT zbTJtG7yWS0ltIVTUmFeHDBg3x4qGp0M@Ij~gR%B6WU}@RP)Ge@j$O2M=YDrn<0!_T z-Tm6qbm8ymH^-+hMV;v?(q_x zu6yuozczrO!)yI}z3h)>&&_*%gxZfrSPA+inoc5)$8g~n-F&xl&lM+ZLpYu0mdouI zwR~b1#U?UzQOcUHrD)@1b_fLpg>vY8DhoJ>!W422l(I{UrJfK27mk+ouD!hxHB-bx zgXFk)S6T_y>*y99Ve=uN1j*l8)| zycs#<+df^rxz&^Y(8GZ@eZ%}Vh6-rLgYC=y0S=S*E=!DPu+tzth)b3a=>>+X2P~sW z7*##IuG{nA=`wQPq;9{QqB8HMt1DkbQdMxN=84vCe5~};?jKU>ce_KL7*#A_MbHPU@L2p|?(uIEi_P&A!Nz9X_ z0~dpWy{9i0#le7?lbfqx7$qW4R%|aE34aAcdwSNOtoK99wxmq!dzDsf`^k!7D~sW# z;MVwU9Y4od3}ylno6Ulle#9TV9yJU+viKqrM%W*?u753YJmS@oH+0{D^1%c-{Ct3)h5?q&MR{=wd2es;B7Sp8d@aMiG*c5@ z{kzE2v4{W~PS)4R>(}Xsm2>#@<5s^Twh<)P1_nhkT#31(*YUxG#Fm+nZoIXV zruGjL&g-erKTAAx5mtjg1-9z(ncv+qhTxD1LSAB^_4k9Aqy}r(;v0SPJ@n(E`R^#~ zDHAogPOQ4UtG4+jh~(o{=?^D&Ff2-VM3YQK^%eHDz1{eVlirD=(^1#g*fRe18Y0_~ zPJx`HQyNux<>h=$&jgFe>y-o*_hE!?^d+|e^8+qb=Es8ux+whgp%mf7H&g2Yh0GK& z9aeSog|CG4%vHEsJ4$?7-5stli_aJSbCtvJ| z4$f6OXq|l@zD=oOz0g$yKS%II5Q@jEh%-R55jf#fpzvTEKPfkJ_QiKX54lPgT7pvI zwb^Gh&rVmTj9UGT+spDKJGkoeB25Q>OKhtkS-?J$H7z z31?1b(DrfB=9m5$bEo)EMd3?_E~Tb78;H~!Xf*Z&Vc#n>EXm2qFiBxMS7kkv)>v^# ziA1y0x7vq>hK5y4tRn5dg8trNZ8X~ZbC;jS*TgXPuVc|T4)^wkHeQKNVRKhozbgYQ zqpNY=R;!u$1ui6cLU7@aXI@a!R!If)W8TXVwp4YU-^{bgLzWv|KWttC;8 zPHW7rdsu^_3(dzDHsq*mW_H!Y#1tn@#kCwqte&@XcrJZdjG|l)SNh+YMEKEB zPZt}_`Q0BhI~r(J1HQ8vA%UiN4fmYSdt&0TicCxk;Ll$eQEd%td3u>y%#*MuCOrsj z<|Gml61q6Zq5gJ1&sh>o%Gf_q&HdjAOniyT|O?VPaQXrH0Ze%imF?LNwu#)4Y6# zV``YrZ6mEP?tzP5nOQ@%PML)cbjdGUZkwfwRMcII;8puO;rPRrH0>D@kLNs|%8g0QcrQuY*xBV4bcdy-nM7Zc<)FO-Hx(#i4PVjhWzHeH zk`!KhB_(6#EUcsH$yuY?QBC22* zpvgfA8<%)B(?v-8~jO@h7wa9)heSQt{Pv?L|ZyOk@YIrq*Ya#)Q*fKDf?$sJ7ntx)i;a z9BETyQscPii2At{ddEpDLPiOmgScyWnaCTU`Jq@;{8NOiro zI%(NlV4zfE8QLMn!gVp4cFu`ZnDH5y>}&gAa>n7lf_?FANvXi!sFo*d{| z7!$0ovseibG4z^cASa8uiXSi}DUJ0ohRR2fwg6H;L`~DnFd1&y(_F zMks1(&;G-}!uF+oR_dtsFN#JnOWp^*GB6KP0m~9Hxw@|86`fO4ZjS(DKc12V z%g2#`fYQ=>l(Ml`X6uMJSAi*sM`gU;v2a}QlDKfgTaav!Kt_9aB&N*W@CPH;hrg#_ zZy^k4;h-jIe{U)9(}&x_zVnSAbDUi1>VQM@69EpTbS}$JjQC%iZfSRHYw$8l9Bu_6 z9;y%w+6rmhy2WQtTB4(dW&6&mEzxN1w%;#qaC|MZq#O(=49d0FP5R=%DN>=Rt}jAD zdxxNNt?fG{@t_nw35q5%$nje0K`NetKNx+8YnxbMEFnetc*=(kyMlchBq-)vkY9n6rRbOC{K3%hI=q!s$C(R;X- zIgnyRL_jPVG`6hy@o3ul-Zihh5j4OXGUw0v<_gnY2&QLn*?k$a4=bIPSU5lN22m<2 zzF1{e#xuHjB|u#q8I?;|_YEme*0w7p9($p)Hd~ma_v1$<^-=uYdI+gtv!vvI-$?V` zlmAn)p_Rg0yvR|?{`$sXv1sPj*enNxq8W1KM1Y}kjA<+2OaEN8qQLOJs%(R89j%Cn z2#f_ZVlE8OCSZjQb#;W!2=sDJ{)@<1Xv5{yi*#wb!B}q`zMof*T+Uru(1s)Yhk`oAWmJ+1Er( zzjr(b%s(k9>AztWaM%}A=|1;g2`Jh6YH=#5xaFTau_=_y3!i3+$mEqIyFhsam>ZU; zJd%73i&{XXXn?_B_OJ(FD@QTR9G~e0ZFv0uUPU;Wh}NZ-nuSmQenV>qNfO9S8%r=| zs{06d?hG$qB9yu;lkmuydqii65QzY?8Z!BHq_&lO6{?MJW@3k5@nqYZF1`CF$ocuF ztvx;JoO$@I!h!XTFBN7{y6BLgAY6z&dc<&1g1QsFtn%46M0+G84vNOhNo)WMKK;kd zKzdOHMP;RW;d#a%9Hi?v<_C@}afB8Wy#?o$lpG`h$#(qX%JVJ3@@mKnq<`FbVt)IV zEG6fn*JfJiLDQ%&8(dV|M2cezwV4m#NGf2AFF!lWHTSO=ceb5J;L2b|W zH|Ax^%N>q}LgR(adXtl47VSaGU*CIk{&3;6sxiu)@+H9yWa^2_3L>K9==|l;OB7kU z;0|PA)!m4=D?GRZwdz($j`x83aGi2)z(x}E4Gyj;1;l9NXh-U+$DB3T2!t@}pzHBw z8>RE6L;cH-mR46+VamgaU9@PJ5{b+$hW$1m^5^q{_K?x>;X_$XTSkT0qtioHj`&pB z0Ke}#a3;+=cTaehQ`VM!*a|9Hj>~R8Ep5+`DQP(H?fW>`wPsw0MN0`oKRCo3i?JBA z;Gx9uQWNQudCOI3ITnk#^GcI@`@``u$;pkYmCcWOuXGB4*Z&L=yKvWuX{LwXUZNM!l#0AJyQ~!YJTRl0Y4~xxu;0Swn=v|c1?{z~+jFva zMB8oag9?kimfoYptXtfMzCIjU+O=H!T5~W_<^Mc4mjy~J*|USrx<}#+@%QmzHUoU^ z0!n#4K~?5bSm#XGWM)%{ou@^aaw41c`B^YX)`hsKh2XC0m?v~}{A2-JOdq{_Pa|Y2 zMR1uBH>w*~o{Wqn%=KWHx!kyw5n4|uc51YF!u&{}^TOdPUPv)@k#}`x@!-@4y9TcBr zti;61_mMNJ`U%AAcs5U)+NXV~b1Ioh+AQ*6TGn#fJKS+QP0+u%YQ!B1^ZMW`X?h{M zK{kz}7?MO(_n#5gt!wAo7l8PA;&!7|KOcQnf=;~uD@r_8`S$Hg5cwL{ z)I@;1nnn_9o#WtoD+C}u*FP5Q#8Da+4ZTnI1%zW#e%m@teYjc%ZOM>ra6cQ{t13pi z`!ocBatOGVyPiy%g@M`X=czS!m5x^I7a~2!8C_4yI`>VX54{IYLdXkQpTi;}iMOOK z0}TP-5`2-Mqi&U>&e3UdO8p2>U;vI8WGHBpA_dvn?ql5cp6Gxp7LpIrRX7SBS!8*| z$PC9s*Eh_eDPKG^oBinuwOVoD&J0)1``YNr`lZ|~>a85pkVdPW{!9riHzL&9vY=vn z)_88|ffbEdNOuUclvN~gGA>Od0X`MdzBmn+l!Q>|wytd}EtLWw6$ebR|do#kKZ9bJ~8l0lBZ|d(xI<0%2#|ZpLenY??UpQ{}jYd@H-_Kj@ z>PK}YXksh_G&+h~G*-eME)Hb>IE0a(`V6G-oL`b-$>YY+iw$>kugDD3jO(onyZ=q< zu0F9)(@SM@m%eWC03Bd-ApV$jXLnb=j+@Omlx-kfB@c)=SjHGQ@Cz4B9EnowtV|C7 z@{pk0);!Y$W$-B9T>kJ-6uHwR@c17OnwvK?V#yWS7HrYJc==lBgiC9-$@o|)_w;#b zX|8nfLM8=?j$aQ!ScG86u)W-a;9Pb4njdj_Un1=94_O%Ct7S9*6lv8SgbzTrnSuD} z%p``@`mi44C0}c-w+HT>QFM2Ai~An%!*=2ZBB~qa%zyTLwnuO2Sbwd~xMdJme5+-M zz(!nalk%;{I<>gB0`2A=A8f3x@d z-YQOH&^Mcvg|&)fJWydHZx?E|$1^Kh2)+U!=k61$m%KTGi(hS>4s%{K8tkerO68ts zuB12*-X5hY$I6Xzi}OvO-`CC%cXfkwoY~5aMnmA?qw@}f$o~L^+A5X0V>8v2k&=Yui zT;n!zV|-$=)3H8CgzaY0zXT1ll+opUky@|sxYZ z6Vz3_<)zTn0N;mel=4o=&3&Dc^|gJ5lsEA;zc&nNg*lClWI;@FWa8D_!MBS_x7#lc z)L69l0yUG3CIQd^)bSAK_Vv9p7c_oev72r>e@bUzJQje9u<>r?PtO&6BttJd{kxU@ zjFJBDH2PXR^J1kcCHq+dfwFt`U?|EfEaae70hWiDAQ-OvUDHd{++Ieg?nN85Q=0%b z8_Hkdh=74#CcK0lS5x1YUp#tqEgdw6KmLpyd`xYPE?;vhMu08D0HZ8S2gND=J}vxM zfN6u_(&FWT#=GSMMm*AU%A^v{{%=R^q8INol-zdB%^`WE&1w6onJP~u4u>SWu#f=8 z%68Z<0V2Z}lu7=41={H4Pr)_U?k<(KD!uzaT_rn)qPh_fU#>tJVRS@wrROpZs-A?T zLs8r@EBwwE+&g+X4p&v4HQ9}WB6q=(-gqM)mH#jQmRKl|IdCP;p8achdD9b;=DNzN zJ_JQZ*5;F2dV5pNcrAJlWv3$9upbt-jxEO5HT?^7|Shcj4bL+_B8m}=-zU4 zI`(9+S|>hfTB$WCi#FgZH^}|u$^gGF?bnjv!^ajKR|Zvwv{0A^Qean;e^Gh)+C3W- z`^OPEM85d(W?+ zd}-pPCP#}t0iAGTWDm<-PidQTa^2`WJCfjB@&u|3$MAXGV7%*e?fDTe9(Bgl#Y=nf z`||LJyZ<5cSOZZQ8*b_tk%nOig;0Y)gKAdBDEnLb$0gA=>YU2klZZ%5IWA%b+^~-R zx-D1CrCK5JH#VP?U-2Ua@wd{5hY`x%E$+ZsS9|Z;g1o_EBSWIvnA@nv=ZV{>P^ofH z_5G#@G6ej(Nnnb#>Ix@^Z7RpW$=ruq81#$9=*zI?iB3a|c%p?~OuQH;@ zvTfFpEgx(lnhqj`6aQzUgL<2a#ifpkNrj1-8wS_1J4dAVjy#uwDxOuAK>DhP2!Hwz zb{qiG8PuXc)g8fVn*C;kc075KMO$$bTe*ifs6=_oLL}1)UrT-d+&Iqe-(+reWRclK zysT9v+HTVUU$21UPc|mzjg)<0kSt(^d`Av3qHzP>nXZvz};F7 z0B556S`?bdVa9N)pI=?kH@Lf&)9A`)t8s36uHy|=^Ajmt6v#ynJ8-Zr-jEVedgVi^ zPeK>N<*A-BH#FEK-7s|VSAY8_A8M0%C9v4gyD31PNX>&uUSB}uKwpIwali)||Ki03 zWxYoy2d+lkDZE{89u(``(jMh_L1gzi^Lf8b2bPwz=_9M=jvF22sWx$j32o_WN~=^TLu02JHam{?rV`R`;(`7!s8Datn-tE%O;5%)+4FaV zPxl!Eb3^3y=z3JID-ZcK|3=uzFoeE- z9no8p?LZA0&&o=iTPfw;@IH`3LovEZ_JUngt{=w494CZHoSmHk(YsOEdgcR&VDOT6 zacSD1P9od&5{6~GzGAlJDKL*>zIW=#{Sk4cvF z-ubx=@YZ4-6&2NH_OqitGBP(M?3i$Y)DnX+)#Mnv@JEsUr@J?@CB`m&$TlfCmDTQ# zE^=T9|AkTeDwnBsL=BsI{C$baEnQ*pu!}iOlJ<$0)!r;-BZLW1YtodRALy>(b!Cq* zC=fF}K+%LM2vc;w`YwbhRx%Civax#ksOeVihStuL8|oTjmiiG{t1Bz@1@pc zA0dEF1GARL`(ZO_H*W0xdDmu3*uiGEIm6rXZglf$?>VxQ zg(4#R?OW;>99jx4F1%38K}<&w8nMqEyMOU!$Sa{DW?0XPi+BC?@e`lX@pN4}irj-bAZL@9R%UQh)WUsSc*NR%6h!cmh%T*Sp;qcaPl8bsKs9t_^$&)}(~7D0dY=7>HjMA-h2 zx}+FNwJ^SH!Y@n`S|~rVo&2ut64VA%u@}3k!gaw=9{sqS2K6(azKTmFf)s2Bq*mU$ z0(|aH3#ja5njCAht=GUk-Ge23z*=MVG3h!qr><3;im${5T*>fo7#rwO0eQV~olb%U z@r?$#O6-0f?pBV-DiTI1Jli^aP$LCQGj2XNyf=$yoFd@-y~{>s;5ij5u{5T_4Eb&O znia~>%EaWvsL5RfBoR^MtdSOV#`0sX9Y4OWbbd^x-~Kl>;QDXPSSe3_>%E0;c);HZ z9m)40fO&+%{$^%QPEK`A&_u>Aw$*Y&O#-btN?ASe8c1Mt(`qEOIJH!2oqe^=r@hu` zL*>~hurfp3Km=fSJ+<7*W5Sr*x5u_%HPPxVAf^3D2rWumarHGNEWyyCT1 z<|1#aLg3PR?yvdE=W2%bm6g@ixrYxfr1#Cs>7Pa{QH>xkq!irT;}X)KUZ$uTW0x(u z{ZcZ4$WQqp6GT7}-RIP1g0mLQAj1F{i|hMxB&=TL)X>m?ri7VLfz!&S#)#s0kb^7c z-&H9>W_h}sm5MqV_k7*#j0s>*M>nX9u}3K*<1T1IA-3kb(yt_vDC&ytt_W*>E2Wy8 z%hw+9q^$Ku5IpY;i?iHbz*L*?^bK82MCZhDDS!kFTwc_cV}&g+1L0~tAQIu3uA$j| zijFCCfOJwMt)LRUkS+3;yX4L5ay?55V(~~kT*QL*HnNkA@=eSQTVHzDZoWNlHLW&n zXQ2*$Bpp4y>p~Y1%*N?Mg#t)Lh-H95>FET-vF%@kGU}O_kPx5u04LuhCR=tQ53)A@ z#EGV_%N{$XtKhm`4^5z@r8R1@!dHo5h`2s!mdfzcJ5yDdPAe32zn4Hu5AS}><7QAh zzjh>2^y;%MV-G#+#e8~KRG1OO+scaA#_8@ zN)p^TFl;fo_K}4Sk&BIAp)K-)DyWBgF|Td?a*$@_|q@kY4bxg}L`)as9Wl2ZDTsqeoC#!;H zAo#p1T`XcY@G&NJipHG&rU$p1n;R3ME$lmB6iuf@D(2Ns#61!Zf@J!jrNb^)Gy0DS zjA^CC#Tqn{xcKeB@qHm=@K8EzRDA2)=ck#iO3Pq6n z)_wbtQ_QAdkD4Y|xHTQ-{xMaLXN5N;C3b81yogS*@KU$&pe=)p59;vUyS||z{PdSJ zF%xPawV)ChI*N$vj#J0inoa@7@vWpSlTEde2__Zp0T#L#tIkkoXfwoib{~Vl9)viW9E=HS zsC2Q^g(0ykR_AAnx=CbcVuy*YBnm$s*K7I+mO#0=ez0LYOk|trv8q{wa~=mfQZ*9u zLDRmh{#DXdfJ4WWn;H>-j#Q6h)f$UOSLh_#SgW@t{H2Aj{P`ZF#1vOlfRKF>N`X;I z0nCPQJ)Hdoidlvts=KtGOby%AKwZxd%tiOY#X3;C_U8lWDb8ejCY(}F(p_Y@2ytUm zk}U`O5&-fJNy+{FhcbwX5LDIBk+p-m3??-_jBx~fgch4;r>>ZQ`|WIQPvZ-lIA2>= zyHXgS*ek-ux-+6O`!vEjP_lc%$~iUfXgi}K=Z5;go}rGmV;IO~&Pn3&I`>nu763W3 z`Bk0B(ZF#>!PibIutNlcu>>~|jg%Mv`x#BBjFj#j!XHpFQ3X~5bh-uHfJYC5&Vrmj)S5AY-M^KRO-OI8`0xS*kRq|>J7J(IE?pgxI~0@CLY zSu!j6E&O5#m_#A)@mm5o*Q8kIo&C?MCXO4oo3-5PdnYHir zm$)Ei=<$OG@ArZjo76=56hHquP^nj~Vp@4%HJ;4&#A`T1`YAQ=QqS@6`O`JCX$int z(@T1-r-~*WAT!vZ zU6Zvj#>-~!v|rwsRl;pe+4_;Y&=b4BcOkH?L0GFyefnb7=Z5KDZbM{vIcVxA2Vt$- zJ%WCDVF~6lRb_W!grqfJ^p-I`dbrka`}gK3kv>@9J`N1r+*7`d!Uq{!)Qs=$(C5R` zvlg2!RwisW=tkiqCLyMeV&9UIy?LGeuRyeh{zJmVZl|8@T0!W-l|j(*2Q_=e&n<%E zPCp=>onJ;rc`4Ov1qaoPc=>P9oBIF7Jo|9To0az5RxsW5&z2?X3Kg?m9~txn77$M4 zwffqVDbgyp_sRq~0TY-Ce(Npwe#OYIFj0fSrxO4uJp+S~!9jU@hwa6`%XEaefNV!& z%HCT1{bL2>IBv@}(R=+aHL+VxPEH-F*LV~GX(zt43oRUF7mLfkMyGF*5T#84J7DGX zScq~J3Mw{)GEDPK48G0GoE_Q=9}xs>)Q;7wvFWEJBy8iS6;>p&IWY9<`2^KxT2z&( zshqP~d&>r}xsL9BbZ1pP^#YR>IOt&E!<^eYVNh{~S{6fG+gu|1Eyh`3$(|wXS@W*8 za|SXb^wjy4o0I+Zs$64?v%4}-n>XCs|1I@@X@oXM7JfWzj*X#uHD8(&$IBE zwD0ZO8(QZdKTX`(zV*6E7Vt7D*7|tYhuG zaN>yU1SursexHlbAkXfOz3G`*Gt}1pWPNye`0z#~E_7A*?d)!Y?g9P;F|qBNasGsf zzP`R56in(f>7We;UI3bRpmagp1Y-*f)c|pe`yC16$p?IM(oXr4CGKkVISBvKhpRCv zm*dG}v&9z4u&BAxFqHsElhZW|!;VcPG@JvxbExSh#bY}U;l{2p!qUqeQTW2j%oNCl z;rULl^We+XE}aBluaXi<%@%0RiX-wl6pA)pWSY9yN4)p<_sUcSyjR0>T_GLak)Xn} zGL4(v`T4rpb2Crg&puu;i{ilX;{Y%rFMPvte*9k+b7LA!FkD@#$LN zqWFQYv(Z~8kl7hcLZ4oj1+yt9rd)je zIl*-nZJ$=izVjW8n3rSP>V(>qIxsy8I@cjCUS4yO0CGHedbpi`c{IPk>wo!FNe>0^ z@5;)Gu9;bky)ZEXdIe}5ly2Xq^p&~x`*T*6amAe*5Ooc~I-7i;lu|{k^r@+UBM+`e zKV($*&OOqw#pSc6^Joc~7CmQJ$pygs>}FW!Jc5t#fX(dNEmrmEXa72;R?O$s_uq-j z>$mUXf^phq!=iEelTE#WX?nPEU1cZVv%`mvB(KKbXXlY$;d0A2w8h-{VzIYE0;e2) zAT_qdUdm*h%<``9^;6Xz>%8_R;@|dUl92^yWjU7Rv_c29#5bH|gi<+ZjVz28)s-vf zIvyVX_&}&UwybpL4mEiEoJ36p&(&H-MnXzB_T%-rlds)FxH9 z$X$SmM|Fl>>2P|>_C5PixQaD|2w#IwE(}Bx@?*IXpZNYh?;+yJ`Jszoid^7>o_-T2 z4wfV{d7j!^;ot6jFUA1Yr zFCV^jnLd(b3XR3u9?0C>f6YA-KeH80Zw>YTB)vkSM~BW=n{AkRKVumDR!10JvJKo-5>> zZ#YMs{bJ(d+oXT@?%gvC3Lo&xfx*H2A1>h1x(Iq+&R|$5hlPmX-f#p_Jfs$s8o_Fe z29TzRCF(^6#AE&5l~T0mPknt~wZ`5YI|2do^T(CQq3%-s<(*vpd#jhN+$A)IpBogr zXT@zc+wzC6op@`F@w=XQ-F-IwgeL99g<;{OuI(e=7;$%dSy(1ahDWKLQQQT{(QWV! z?eDj@(LX!~17Zjj*O$DCimPDs1)wIU^ah?hn5{1X_Z?est3eKR8s6OzQP_Be;j%D@ zWkL#+ZZna2u~0|(d9iPsExL1vk`6R$~04eb`Y0qjTapWBUi+eP8;G4ZQ^InY9)&NvurQ{8_wU0=X9F0PBBfIYV_x^_=>RJ%eB1l&5?3s1hb zwt}yOZ=}fKt(diZR`Q>Fq+nP5(&)PQ_A!HD7k{)U7zu9(3BgwN3-G73)DdJa1^}$X zKx_u&fak}LA7z;GDE>D^xVi6HLIIhQh)wqunaGmxEQi>x<^y~sdHIbrS;uR339nzrsBwRBxS5zQhq<4W znmT{5t;nCwL)MMp&}IlO$~w~lHCvR&)g^IK|7Y}H%D;t!WaQ^>QY~TI0(hPC5I?c| z`!!&dlq)NA*$y=}5&kFdHucjUYBqhD$gM_4`swFBlj!^Sv8koF*#3E;15Ehefk;PJ zO-ghB>Ua_e&}AH^M(Y zH^_A_)pP95*xr=PS=KtJxS8uw!&Z7zA*qt*<1Zt`pPy=Ec-VwD=;g${ci3Q8ZN}D* z2udVOKb@+vOk$iD8>T(zHK{M<)}RfPwGMU=h?s>1iZ^dX^GZq>J(@3+89wa(yF3X3 zCPuj>yv@uB7D&E5IZ)>|eG4K>Dt!FI?Bd1&z%|5Ob19%Kb^RVX&PJ0X+yHSOOZbq?duqYRcrHY4v4``~lh~l%R(|EKaA}AY*qz$UA6~r1m zfu{g2clgCSjMnqnrC!Q7*;rUFprHPfdAUnZ4+X1Lfdz*T7YBtuEFAp%_nr4=M~{Ih zS-|gn0Mjdq*m@`}=4;C_LM4WdG<^sc28gKcXbb-6(NRBmtE?c=!VTxBB=XC#n>EU< zV%PY49w5Uz(#il}545C~FQ7rJL=(dW4?M4ipUmt&+$-jSM`UEb(7#?Wr^Z@j%YoG% zrR=a$k9>qrsQu93b!JlLOsURv%jd?|8yy~ox!*TNsc~Gpm%&hauz2k}d}qfEYZX4& z@NA9x@#8MmG=QskTNo$?$j*!V-J?RtFuDA7ugkJwDrO|F7X-s#KQS8Qcz?8F3fI)e zm!Z3SBeH%?)SqRJDPZfo_s^xv!QZ&qBJ`Zsz2EQ8P`uyycu^cSD;S6nhgvox6C4ag zrK44@N4k|(RIGo2=(N>9rD%$MwKs)@zg>+}I>Gtm47bJkoqPA52{EhSVXp?HZ+(FZ zJXxa9>cl-~&U3RH?^ZVVY4_Ll_v;$UTBDpb%1UoQr(pXjBLZY{FkWUC7ZXDB*S#dO z|ITKL%#R*Q7bn+^>XtXc-;fwF?r|cDf!e--f!?|HPO>OvOHZR3?_F(ZQY8~S^TRIO z9A^QcKcJ(q`Bb+3aF+z~TKGEGV^izKgrCFP@;dz0Q0;rD(q-kWi=t)dWtmZHu(Qg) zX$Jk1;fen_Qa$m@+E?(p+i@5ctCb@!BwI%vluE7`O9z>vWBH+%ZY6S9oh`byKd_a=o&B6H=&gkkjx#G86~!Sn%> z@FH9q(%|34Q%_9nD*f;QXY>88z}Zf!=hj4(Ovu85?}6`n-=|MX{4^b*BsXi^e%%S_ z#DN5yM+~#S4o0OGd-7L%lp@Yl4HspY7R7Kt*F-3DH9R8s;NBm{Jk8-?tE5u8J;VNI zlC>5FNh}HcU`3nTJ!BdX#AX2iXVSjxj*B=u+ZV$|q+q275G$(y^*5+pZb847isi+( zkUe_QY-s6yJBo*CtgLAW%pY>}#J&!AWE4{R5e^{8h|U9hdJ01>CWMZTwm@#nv*+DW zhV#9$XB_WmkU(}4fP$8aO5|Ym-fZteH~rkcm^_9G9w5D2N1rFM+v*mao#-;bJ93ATvl@J9o0H=)=>8L!eyG$?Y6vo|4 z7SUC0_t_OMm_>n^T)1v#(-2! zFG-~v$2i54Q{(S`!p-=AIZCMyiMQqW7R)ro+qK4Kdg zouCi3v=B_M_L-IxZg?X%C(e(2aWa{ZJ=A7f2l+EK7Btj}`4G!2iKP3fm2rs)MFDqq z@bcKhuD`1f+twR~g3J4|i!Wtf85-ulL#e#IuerS5(V;~1Z zHdIEJB1)~HA$xoKHLDH#ua%jmN>HESe<8&X)jfm9bUFWNX!I-|-suJX3XgZ3@djmk zTt+D^60EG&(um(Ll;RB(sZz9U^rt-kM8;_o@T%f8jmx+SYq848Udu)2!tw@V0T}lE z4?3?cz|ypKtfr>k#P#gNyWFInxb<-8A*dA)2AntJ@j)gsrLJ6w5FKFG$x(8!)$NUx-92LXtj?a+?zlrawjR z!ZL7!a4H#{NeO~KPdU9k-&cQ07~PX-(uOha?SASfHp##p8V{ZU10%;b9Hja+nTd@lO3)|hsv zC4|H^qm*<04%2t?o8+1)SH*uiM%UvLkzGzzW+8_t8W_o8jU@_&vVf#CLV{p44-Y;f znofimjwpcGml*vIED>#>YZ0*SK_VHYXaGP2h%m6Uw4Wg-^`1X1U+an6&N1cdIk4eS zghs!S7g-S(E}Mv~-Eni8t+}x8CB<)C5s#rVAeO+5N1iTAj|*!l8lhbO9=Mj9HBdvk zci6x$g^s-9;7GkB>hm}SZfaBR$b~ozrh-N1+W*Sr1&p%IaPQ&{7Ie9C=n=sKt%g;e4gV*r>~tm$R!jN^^D$o2|y$&zu%Gj`1m*zbrg7!A*X^fB6h?5Dj1RAZt1kGn};6YBBF76 zDfW}kw(ig}bII-=*NR@QWoe482pR#z;^%Iw8ZjUg5KLwk zlzNC5_;@((7VWDg{-y5Zufvl+5dFNHb&HIbN8Z19rc|Y;6&O|cPNQjs2pVSnZ(;SpRD;EGiEIGI4P@M-j~L@WXfNJUhCLWyVe4Izf0@8zgW7 zJs;{k^){!nlJxv&vULmg!N6?UX;p(52GcZ%pEkfK^>b+nbhWwf-!njXr8o$|BTFv~ zXIl!UV?&IP1O4s8mYvx-bpi$2vErb*U{LY)mbg=88YX?b-)UL*ge9D4UV9891s4yr z*!wSvVgdqSN)LLV5Sq|!lNujh6qbj?tkP1B30PKrhblrTQy24O@4kzPKI*<7 z8fC(#K6(WtN>w6STo6MdthMi@JzAm)4Ht|=U;_H@Yru|!VE%;%hW7qCl;9YM-@(5` zZE>(Q55S95Ca?g$yXmuC@Z@oPe#^IjAI0W1Z2uk8S$wyY*$G!Nb0iBi{Qk#NvmBiO zjc65dKzIPCgR$Z~$oByqFf4ltZ9PBT#EzUygs*Q*BHC>00l&BYTI)=|(Yh(~viys7 zet4mS9A^H3LwoG&n>9|qG=v*OJAXZT@?HC6CWj&;a#Tt0qzbxmsQ^OnLFkKMux~76 z8rb;<+^A{#(7(FCj0{+4k)l>u2rY~_!&wxYy6nZ_A}Wx5@x2Q$>Y9#-x#qU0K=n83ZMX;7d?L3>-U{rou#4Cp&++wXeH# zw$=sHbbpS^MZ;zh8D8~Kf*p5qGBS4)P3S@%@i5aMKcLn1c?j%h>y^-2oGL}idM6od z>a!aUtZbO*hTsrw15AtZg;&~v^f^T z3R26Mtn-s4tm`NdPm^y5(!62ie8KwWR!gacmjd%cTUvC-hdUc>EZ?M@M*E z?`-GF4-mY9I|-ZT3}^skW(vScmS}o00B;v2ThBzWJsU*0K{Vnbti!4TmoJburUp>`)K+WEf4v|kJ!0Qjd3))90OdfU0^*qE4I>Uiy{Xwaw$y7!B z!)5WPOYX1tH$=yVtF3Aa2H|+qTXx%<`rA>nj)xB(X+=pPWke zuwMt{r()TlV1Zi;9utnC*LwZrR`cvBJYWZ8(JU8b!Pf0VEp%ki`C-<1JE+9JJEQ|9 z(H|+WxDQ!5bJ%|aDj{gLBVbt*Ovq2YmJ3p`HZtr#3S}bv@4tw(TR?ve@kQ&83rlYR z*)>S-0<;T{$L3TRGLF;C93!~NMHj;h9ZFU)g`c25CE4H0YM;p4MIwMdm<1WbW5m{l zK&JlMa&`q1xQNfaMZ(DuN-POQ(7KH|iC$jSI)j{hxF)dIGWGz0kq|o{AV9Z_bFz7U z#s{bc|SgW3E9hbm;kCbE$rsE`D+scg%;hKHFawY`gn zVH=2Pdg!(?G8lZ%k7s+a?*QiB1vqyC*!>(fFkw%`lrICt^ecuL?CCe!(+n1;uMG_^;R~Sp;pl{+-m8k6Uq65Ld*^+h<-V`yy080s3>IfOipt6>&>U?HvRyi4qZRX>rZ6xU?C1z4HzP9> zN$1L~TVzmXNT_-QR&kSL90Z0TCQCD@TMZ9qLGv9_`$ft-YSK&~_ORBtGczzvtz8cl z`Sbz^&;OZ|PQO@~1?@ti1F9y@6Y6+X4xg27LI#sL5oX2cppv zyiv35K26X)!$;E%M`1FmumlMQ5%;}N+1)q2Mb0&zzI%5kUz`yUTJ<@vQD*PG6(EW1 zl=m+qy%Ra(eTrRDk_X`o^3QwGziFG zvpW%2j*&!o2Vb0N94v5G%X&_=>pNj0i}6Mn-WJ?T2-1in3^0!cB#`)=bat9O3>dcP;>uK#cS#M8GeJASG>d>l`{Yc z1ZW1ip$^jXK1#=r(SeoH9Ea;tL6C%ZMXL9YUk3V7M%=~?7r8CY#)gK6Rpr|-B`OxK z(q(FLL&u{b*H@|(A`mdjQ7+WAC%u@3uFD@^58#s*h}G1aoag7PwCjQ^2evzyk*25D zod?6J9{2VppuNsm>`b99lg%b7kFBHD9{-VB$ec6ZQch9G1LX_znYOUU zTAlMNybX6U7^1?rrdaI2^J?u3eNM`UFM+D`+HlC>Yi8f%KBkJi@4gY&H;xk6%xAO^ z-8?xSR5=*G4rkp*1+)|tj$!KC4`tTFuXSH{p*j_moTcvYR?>NsAgp(g@bMnCAMPAR%rZnglgBAJFyB_7eoMjk6Kz=AyjUFk7x>U(Hm(<-I6Odhq+I- zPLPy$^sHY-R@P8S^~d|fX&0?Rzj;+lL5FFAt?sdB58c_BH_H!hDdMZniJv#Go{?E* z`Ioy*DkV>bIEOIEBc!VN?*louywiWW7N|4zd2pRia&ymICgtG~FP8yB;p=Z58DA!f zqIWB+KpsUlg9i>j(HDq94lt3{(J@C{&9;j0B1F^x$LI)8d9d$l-Ze5P)Da88(bMxk zTuj~8#zTq%v?THzs;zEWI%1bs89%L>RiiS-U091gfC$UOz*_DHbx8F_Om?u*d=16(E(TU|?Xh@Xh8;a60 z8)1alaHwLjrarw~a_{Y3yt7e{sd)p^eS_OqLEzw4dqRhJ9*!5%wE5>8R7*)DNM{?S zIJ6WvPBs$MDuJ&T=D+&B`Qs9f2-`!4_>jQP5x&-imR}vMO)~zYG^Y`d%BDi5KOdJ} z7xUyX{_o=>|4M&*M6LaT;bO7Hx0vXA?%OW1t{DVu1@T`RGGG8|98y0e;>baI1+wa1 zqbN<7)Vf=7j)QRL_PcyO(~ppb^T@=%HI03eO0i=wHi_T)P1p)?3j@6?!5}7D;Ejsb0(j9f- z!(r508Wqh``h+_Yo*MkJW(~rusKJapVdqT^wY6YRpSpf?9rNbxGa=+6c8-hyU!9Zy zpMeblmbvWeNdY>!U^iJQCOYhqeX3#~$$myW$2{&42qUb$<{k2Gzy+RIGl zeER@1!KuP4KmqAk?p zMz@@%u&)uV*t}N3JkgrkQdXl*XDy0`DN8Kv!cs;A0t@Xy(x zAaK9Y)m=wBYYZ2!|6PqYJ)1H1Jwj=cus2Yb8La=hH*6a}X?O9lRd!vHH$M-$|6)Iy z4DfaMi_4Y$K2+d@h3Lf^L|8opxUb(oRMSuaQV&Ii2s z_YH?v_uKFpRW59reJNuz&8fJ3yMLX~+33Q6oRk;;M!e|(`!YP@U^`6l%+)-upFgh8 zarmg1{$O|;_A3jrIAw58)y5C}6*yD6%K0OkZ>(KoGfg9#O)duHgy+2Qb{!i|pUfo) z8@SxeNuY@m?_BKM+A$(QNn*)cIr%|i?CR(K@=wkKe{s%K`K=2pX07{Et(@=W#4zfM&2)qW0? zR5VF6AlQDs0vWN9vCpob@Dc6Byg6H7n?Wc$q))D6S|8dhyQ-d&G*r%J=f96z=zwP( zZEJ3ak6BIVbSA|-hs{Qv_zBfc5OHfwqNz9Eb<^rVZY6C=x4iO?15=`T_M=k^6Ka&k z;3O6mvh)sYksB1NJ*&-B>jjKm{s?_>3|5F!2wf%b??7NhDs8r1x6)bH zgfF~q`m9e&-kaSi+_+sNeQ-4+nPjMJ4z^enlI;MeL~|soC3V%wC(p&3J0>Ia--~e? z-)ortx{{6$qmzrEa|dFUBGn9r1kfUtM!n-aj(Q`GC|P+}f0V+!eb4I*4bKUL+Z8%|3sh=Pv#85``!ZwUcX3}7HdznVnYDeKMA=6D{Au{$c_B^C@J zV$qgLt~L88{NveOk-N4o)mF{D`HZydG`?&N96ELP;wL$=2bNhQHvmT+K=Ee3SWOHS zvH#I@C9Br{67|&5RWTzQTiTzs2)?s%D!e$>o+zdIWrnIH=zYY9aw<{bzElo^a&#wDBn@0rgb zETN&XR>M<~PxZFx;#D9hrBrJwcl5y=4kujJXqfs2fz4~3EWcWhW?t$~c_pjOcD#h{ zx{{@`r}dfQkDs37r`n|)+nE=Fb?07ib-93%_8X~LVD1p4aUZJPRC+OY%`HiCrgeXT z^W`FTNrg=O-kaK1+Dw)|_(*4D5O{|=4{H-!n}Ae!VOKKJh|VS3luI3NZfXnrZcU|l zE@Nd-%!vE;1_aL{^+n%0bl4iO8x?1}=Xk$wd zJ%0)KF}kmElx(PWqgul0&1D~4U|!ov-K8=q+eB(1xsW<%YOX#cSt4Sjvs8+3#O+eYCMueqLRG$4i^s0h|R@edVKCC=3v&c*GuqL0cwn%+P!aplBd(#r*pJM+9ZN*Ih literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc3d.png b/ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc3d.png new file mode 100644 index 0000000000000000000000000000000000000000..b9ad6fa4fc4abd8f9b1671206c61b2d3895b105d GIT binary patch literal 250010 zcmYg%2RzjOAOF$eF6)e}gtN(B+2ic9FME${vJ%L zAANuS|Kop;JoM1#u8;TU^?tpc>m8@7tx9~G?luSnB34&ZLV-ZIs=yaN1RwZG$XaMG z@D1vzX5s?^5mMZI;ecM`(SSfWQO=5ry1GstPdt2_JUp4y6&0C0y*(V9-Rwai|8Lk& za;^_?Xrc}lyY#r}ep*M9+}nfEm)@ac+hpf8y|bIDqE@WoohygWaUbPww;HAm z*64p|R8Di{Gef;zDlRU5hUduZsn!!_a{r9Ep*vhFuH&0z^baMm(ihCUab;z7S{3@P z6N__YwLVb?Q9HiLA@`C(UfOIy&q-BF7ROaeE-i!tJLg~iIiE8>(ROfMSuYT}3^Vdz zw_KH|Z_Pdxs^IWVRhV@-SjFS0&I=enn7htR@sk_c4Ji&PxV!KFCwr2&Z2to1F4RZo zok;{5cuGumYA7ubD1ZY53QGZjPOpLQn;?*{00^{Y1p-NCfk4zAe%Y6kpj%@p>Piaw z{@-@Gp5@US1@ngNbu~Zn^*w%a>_(?vV)2~Kq;YLtsKx&7{=gER9R!{&3Qwi>m&ax8 z?2PI}qdTLhLvZ>cL2sW5%!UaL93{9Xy7P?Wx~YG$-4!mG*y)<_-oL!`s;&xDVbP$| z7|`B3wHDFv^PR5UsuSJ_?B38Q#eBMX`5%VEgjP46woYEKZA;493z%G8$tZ@F7(G-h zfhzKcM@L5w^e~q47<&Y399)*?o1SR;#k?s^C2;T?9?0sExG?CFq@$Z)WH6QZeDiS` zAz_T=-cP=^@A#J2yIqerbv$%jYm)yGrHO?Uflp?v7~6M4g96v20t`e&MEU=w-h0d@E5W!$!Fy&Mb&Hb$AV8N_ttdYj*qSWgRwSU*%lHktv;esbq-~I%8 z#d{k88e`)&(5~`LzEbF^*N?0>(ooD`AqHMap@*Ap53+DTIFIHjl#ueCadAk?s*Tvas^ReiE_m(|v{}K81$@3+Ud@m=?2DuQk2AW)?({m{^*!<=f_}_oKTQWP~ zK+Eo0LYaz+AcVqk;5cJAxP_>7DGdW~K(mO*6BDg}>muDQwQH~USCc%yeI{oJM@M`Iuot&I5?y3rU@Rd`-5HNXp+}NRXR4V%2(yJczdQ5b5#DQs)%4E04BuYUL1L)Vh5zj}`vn57WiY&~k z0nnR8TA*pW;C0`Z4pv_F0jk9{;aS9Klllqu_4ZOh&vW;&Jtpm82Om7@RPv=FwQna_ z)mBVpc4K)x1yb{0v9lJUR9`4P!KV4clP3Nk&BTzO zt}$1GnyvFvF{6#V-|l%sksw{%>Cg4wPT1g1{x;Xojov8)vx|sO{;yqSuSs7HS<1uP=+=7~?LP zBgfdpjef9jv8@mdO*F`l>rZ}i3g@f-_XMc)hG>;XgyMZuBK3N`I3WgHU)H%fRM&W1=vujvs95MQ@D3#wX-9b zrU0T_>ow%`dN5qEQ95IHV=i$WA>vr+HSt>m7hF`6oESy$C+E{ACq<%~J|V;H3Jv zz=={O$JMW*zl>yHABLlKO_bKXU)izGjY(Pq86#EhUHkF! znFB(9wlq4LU6l@ac`)cAo%!wDx@~C6g$KUj=pxkES4c3Z7ZeEnK7k+!qW*iRVcD@$ zIM@28xY_VT*Rd>e2m&XvQd@{C^EY!T1_Kk4W!TC4&_d{5GbiHg2dgrDVUvn}!u16q zAhz5iFd5vl^zkE`W5L2z!H==0e2+(PC9>2WxQ_fPDdsb#|;z%3qMTdPNi+!E&+0KU+0(U{gDgZY#c6t=hbv4NZVaVq)K}xwX zz;$VrbXTQq_YhDxd9Sg=PA;v45Vh`Yb{ussxHRU&Q55o)RqELprRri=>;QV^i zwH5b!wK2TUB&A!gDH>}>O#|k5eM0HM=XJq{ojDgK?RsJJC3-w7p$<1beGAjDN6$Q#JJEfZOy?)oSTg{18AuNhhpYZyN(gTHqq6a~9IPp1c zqL%LEzH^w*&vG<>tXAr8eQ{|%lXGeQc8#O^;&DfmnBk+u79Y5L!*6dM>W zf32_&4Hk9jq%AT#1xD%B?nSdBP4%~L->%*m^T@7Fv841rFBM^1*U=2Q63_0)>!!#pWDxQJooqo6>;RFbiT$R-dgh7J2=%} zP8M=%-Z$dC9#L<2jD(^=Xbg;(Ru!IAF&!bJxGKKq`C)p*Sm&FbiuVA-pHo1RY^66W z<^ToZQb2=9NKPf6nXQhVniSuR?NzO7BL*y?`OM`L$^7ml)QguW$y~3MF>B~6PR~(g zc0(R5o2OYgBa~|8+->_d$uAi+ndv7}S#4kZsC;jGP_X^?>>P>xJcx#MtPr%UC%!?0 z5c1@>%;?+Bl;-jXE)*8|%9Z_mLC<<#dpK|X95<0n4aXB+^7#d`=qmOXHpeZ{uv{=j zP$(;5NKHE|Kv5Z{TSZl9x)FFz5GixEHT7xjA7JnW!%Ihe=Tpijf66^dyrVb z@tN2y{kcOD&`$f?B*HwJY5Rr$%$yJn?fuotjrVB~6e4})(u;lr*)PCA&&b%rM%3>J zVk!`(R!U(FL-`=;kZ!EZniSZa<^w;c$!s1pxayu7h!f!Y#o-gcA;byi*#YG6_O`voY7Skr@?I+C?Yd(U4@o@>g-x+STnmd*lO8(FyhoeP^N=kG&FTk%Jdr!K(#0cG1 zXI-MNs$s``epnr6`bJXtFSg6N76d{-pe**~cV6a$a4lYCxQx{FfAYtN&)DO!IP+6gjOFs*{N=lay zIvgeidHIZ3&^Yz2x#QSXcGVH;i9L+{$1Hh~c%{>9+v)pf&w@S0XY1-s|A)=AaWyA9 zXMN|#rILN#io+KaUsCLP2fS$_KQ7I*iypX&?zt3GEcGba8 z#$rIazp%@uLX93i3U5N-CW10e+Z;nf+l;Kb{x<{ihDbU3jaS?EHc*vQQe4=zN2$fx zFt4$<5(HQgxLV5{L0Y7q2Sh|V9L1(Y!w#KvIuQ<>e?jp1IUdc!g<>ZUjLnO8Hc8}v z@%QVWi9g2wGCk%%`!V~Dck@9Q#R(1pHtcN$EBI08+IYpo+Uj|8C~hB3TAqeID=EvO z{-11=g#VlU)SAs|u1rGH0CWUoVl_O zz538X6fs9;G6au16BGvOP4*y=X4)pt#*dSnSJO{MAd)pB3rz_f^im6m6ql|S?<~EuRLpY;JlcGERWY+$VBpvj7({BXVZHEkq zj6O6~Bl9Ge{A3!J7Ql;r_Bx#w$+ZQ4Rce$uI+YBO|IBJ)id4=<@O}EFeE)+YP4r+5 zlf4B#G&A;IW@Rs)wbGq-0Zga}k`ovuXga%)k2C2^tYUbGAZXjo! z!!J$D-MRDCRxgVV9=7yb7yI-A%w8b;T%8L9vlX~SJ_>z9F8_w!I;gLJ>{-sVGoK?y zcML0{iLjl9sQ0o82$D(9L6Un2wg2NVNugN+T8E8pV&`~sE&Msicup)U1eb`ElqFxg zq_);Q-R7*>x@xcj4+T-+#3FIxVso|yXz(*rDbZn&*iwoFrSxdLSGbdJH%5r=YWPbw`hMtq8NVVP@Z+Lnq4QcY^ah{=!?6O_)y9vKf{R`drRiY$( z;YDN~lbT-|OXg+gMIddIzk-teS=ECWB(iAeb4-+a_1DZ-%zbUk}?>S{6@i3^;N#~Pp(lH6cI`g>G!;RJM^S#LZ z^H)6EqPsxdW?-0+TyQju3%l`bL8f~@G{xsC4)FbKbGg0sc*y-p%u849x+p+h#!|= z3Kt;9#6)9mmS*?)WaRvIX{+O}EB#u0j-oaU_fCdqj(Y-MOG{_~0^b&d&E#pz(ovT?~MF{1wdD)z#(X;W4;TZ#In|~LzJk$pp~2jq$V}shI^X}o}qrI)OH@E zPGX}z74mR@zSaeWOR6RXj#lVZgmSSW;L8LEGMY%Hwe%^v;Y7^H`qe^X&E1rB|2e_| zp1I=rhzBgVrHLxBu<789)6P(T4CC=^YBFwaR--e2mP@j!<_|URv2YjO?_I(5GuQ*pXH=_M#oe=UXL)EkkBXR$)J)=NNNo6T!Q^is+g72*Xu_hNAWyN%Vt^CO(s`Aex z?##1@Rq<;$sx&?DIj-UJiBjOA2>YX`K(s!HAfIMch*rJea15w> z+%6Qj`o?jzn`Il-G>T_V{aHWK{ljlIcgCyV1@Up?R|eOPuL12M6OfaV9uT4c@)e@0 zIylhM(!x(0J;94k6%;JS*m`=x`uqFUuqaTNVhl-@Ls#o?L9mrOZ9S1o|Tt@v`P z`|fr$Q00t9)zc|z-ff64jQYPWqx6Rp)(h5zIyG?Ci>6H5~?~J;xB1T;^P%EEaJy`uU zm^t$KfnTdeQ^!4_MHL%bOlpNcM``bi%qX4ED^khpk`O?7SqHelDltFR*Op)nvE0i% z=NILzoXSpQ_XPw5!tOq9!!a`V!ux$H4QvHPQW-R9@TTHT4e)iJ*qT3?Q1%~`S_l_) z{nC3J{N%}#rSCrD?+?f2Qi5dV><&0lHD~uThnrEuyo0}4=N#@Kp^CPtKPJ96oeW~V z#Xkt{JzH2LgjaoaJGw@4*)e{8ZBY2S1Zk0$3Wl@dTKT@y!xb3NJqFEbe$hiA9oG*} zJ5*Fu7Pzs}0x~~^w6Wk+{UkPMkaB#*)~gIugeE3pRM=!lbHI4?4G61rTGtjvDY762 zRh*!qhqjEy`Zs6j%eua#0^>;QkPo&LXW~GLSl7%+QqD@hq{^J}mjACDcz8zI8v%A{ z%0smeOshXEN#_;QF2;?IpbH1deudT5gt-qqqPN?PTOZ#8Sq~=PI~feUP!0N1!uXy- zM><@>=ZEz~vGV56pKs&u++TXO@G&Phq6XL>(uTH_X(ifFkxUj&(HPzJX6PHtOAd{P z1=QfTegJn4WkH8^B6TzDGSF}IaM2T*qLYPQ2(bYT`Kq7F93WOZH+hAd$0eOp)v z>2aT<)}DDD+P0OdfJMDsO_58!K3crGtD>qpF+ZPleP(ri|8eJm%EugG0yOO6uhq3^ z_upC%8=!UgU!86=gkFb~PX3%hBrly`S^13Z%e~yd@_ggsn7<&aWZQ~S;2fy-6%?HJ zxtlZ)N*u8yh)^S^O&u~O_iU6Oj=PYQ*H1^SaT4KWE0Ce(uQ{z5uAsbHlhSfoBf$h= zU(XUAQZ+svc{I-~WX-}|St+k(K=&uek}el=o^1B@r$_*C8qQ5BJ^9pY$^&V^YmQ>&UQ)0~i6mG(G)qGJJA{Ap+7rp?dLPF`Kx_6_)kB*MeG=Km8T_(N$MT!G*EC?2Ry8A6E zJRFC|^fjc~s6N`>q-`}>>eKXel-0!w^~rnw5FF6v)>eR)O)3VZ#+4Fy*6ExcltJ@B zeN6>mYZ>dNm$6Dr6*JpbB3g&bm0Nl;AgaF=X{@pj;NZx&xW9BypK=b>(r8=~ly5&9g53=@DqxUN}HHvxjT_}zW zjY6s+Ds@+lV#C0hsZ5G23lD|6S{!`8QA5N1H~Cn@mM1`Pqo2zda?Jg=&#C=>-8##! z_^&cN?g6R~0C$D*wL`N}TiUz@dPqS@$@r!*Ny75{r*shbZ09rKmw|f{kA!j_eGYbX zBB|~U_=H9J<3kZ~@z@c*j(<}$b=1Lz2LDUFRfj=thW{npE;(5x{BH`vs_8r!rg9>7>DM0qnphDJA8#k?#lWpQWwp`hj#djbEP> zNo|1fIzK-TiD04yxtdS`7v0oR3_}3qdjI-T4loMy6YbJKYJ6Geu8YTv)Cf13s`O=8 zme3=#Zsj=lsu~~$AR$C5Fz|1KND|_HagN(PXlhVbe($J})F$V*A&0OU!qS?dR>iRQ zhm*jfDfSNsS=Mp#k2kS2yuoeie4p0-pN@t4ZX8Ro<4ZNJQ%Xi3m&Aaf_P1nOgm`s0L;krBI+Wzv( zf8yHeU;JkG^Lb#f=>VN-SFJP_6(7)*4Eza_C7o+&aGqrU12l}l#dC&`>*G*H1(-De zD{cnLOaB$+0$#%BZwdnQ83aBZ_`?O-xK| zmtqL4GHJ_9qERp6YNcH6u^JPaRR%7T1xuk*#{f7}Pl0Fzt@&G|iz-Ja<9;$p9da-x z?AI?*CyKPSsgFcSC{>ade*>Wgs_SDg>7Y~_PWK0nR_>YY1nj#{zg0j^dpH%hZdXsN1tUg0ngC#%H8Ia;CZ%8f_u!^d;3Ha2rlI zYuv^`1gsFXY}T?ze(Q|4>c1AUjX%;@H~L7Zpw&Ilq6Qx)HLto?Zh(d}X}}Q;r{XaN z^$Wc6DrwBQ_){*22co=<=k~P`Ps(raT?8JX=jGp-)#3!cKDnz^Irh>j)7m}(qP4?Q zXUCL$q6k)WDgc#CfWdw5?%lw0*h=hS4@%67_!i%z9f|a8$|qWY97->VEBL~Ihbq*T zW`IuVIB+W54PSspw>Cx%3mSP8reBqiifgxuLy~kd5oT71!sA&rh|{}ZtP}~G)_|DD zRN5s$^oH&z6f4PeTgLDh^j2h?vlDVeM>4hTXAkMcG?+u2(dNj>LRNNjFNio~=+oxM z(b@TXM-qB@4{Ruzm>`#r#PUkPYfD9EJzIX2|Eccvgqo8<3ES-je)Jn#*_3)nEG&Wu z@U?7t8~gyD4HEi`AT-Q=?vr+|KNhd zgsOJb)}!EH_4}dNfD<>NNfG|xb#E(SB0GEOSTTmy=Ux!aTM*pvi3V8yE;oNAiqOkx zRuwx2kJ{2F#I-I}vVO&BRv9JTl3Kjx7(&eX1L{Vo-Y&)hCQf-Ux66gIk^YAmnWI5A zV(l(R1IWhQME#5O?h}%8wZb&6d$;Vs(!=)5U{;7Y2?-wm*c!SR)_<*dyv(RoCrN&Gphg0 zcjtRRyNg;i(f|EadL&sH{o0cBn2`qZdQt741ela@3;DAT=!wpN9I3;VGf?;)LyUWdk|WW&-^a}qV!1x3awDyGDpMEng^R>cu~y44x|v35bghOXD8SGN@Oksyf`Wp=NR6xfukL8Ba(rDs)me8K z_!gFHwk161d9M)U4BxflOW*w5aeSn(1g(t47~Vvm8b9n^p^J>^r3Kcz&3W$S&yj4p z{{X^AbFqIOiw=N9QUnL$C$x-knE(yp-Epvaz)$QA1fb%#BpN>iR++!Br-#voW@ROT ze?WA`Jo57Vm?dijp0B;yFvy^2W_H)G-ZJTaeJA-`s|Nv=GFQyKZ#CsXHB)|meuf&^ z20g%3U%B7Cff<4x3({_j-S>K~{?;G7qtID;;ac~WxAl8OS{j-3=~@O^JqhD{C?5261v z)zdh`FVCbmIZe0QQkg(DXeLS*86uV5sNZ*q>0P9&7T^B2#Cd9u0CQ9o&@f7EXngEY zN?gis%-NewiElRg4Zg|?*s27D)ta@g^oHLW+Bm!+a$A2TUj`qUn0vm(JDFd+vieD4-7=NI7swE3*T|9<~!Z{OD6pGNBGj(m-ih3~XMc6N5J95B%f4XfXZjLy8H zHOmwpm__uOY?jrQEkX{0grJo>szMOf!=M&U`(Z=ura_MBH+X8iB^NG*SRAPx(q^S7 zo`lng4VdfQ5TY|ij`(G5d$HT;E>IhVPT%$CPF$&4WJJQaX@gb-KRoO`> zFCN!PIa_Hm)5tUO{0)y9pW?FdXvr>*sc|z;1}<_?EAcsRVbf=>r?=VUIYD%_Fjab5 zc?flHc=!OtnS0HDqdG1u2Z;^g06z1J$mn`)X{?VnJ^?|4_d3%2*?OjNv&$X81lXJJ zXmFk3dn82r=jfA37U4=}ByFRu2lWo55V#{t_bOfWk1Y9lmyRUCK{ z^)DPOxHDh5OmlztUriEU$2=4e6b!ez+%f{*J!2Wj3#gA!&9g3@jM(yjNhcf$q1$UD#xC-M>_v&nV>9;@5NRPqpISUe}KSrw%# zZZ^9jOfB&_YYj%8P?4ET4v?-MAi1s`n@unMw~wTxc7*SlF=wqhjpt@_e^Ccj8@;|f zAXqecwqqv8b9v%V)#can=A$;PkNwo0p(s;ExO4h}esxU8@zJT--?{(1m!ugmVA-XO zI>fFF3%eP^{o`e^)X-Sfu3DD>mx2b9x6dV zp8Dng@xs0%cv(l>F$FS zLaP&8x48j8ocPsTA55Ggb3}8s!heNpbvkVH>hZi}jcN03phx-t{=jk2RB%Z&*W#{d zWHj@7AvdSEImrH%LmVexsPepJs(F}Cd_yDJm*{)V4;+m^15Z|k&&$)mxWiGq&1IlI zO3F%SiRet0l*C#RND@+(RR*afe&)Q;W78Cl43jUOfXz-0rnRUGjoIH;U#Ixu^-QBzPj^j&PWl2oh{$X!c_J^l`v@zwFq4gIdLK|p@EK~95@6Z^shjsuujG~NOO@|?;; z;a7Tv)w`Q>M_c5lVz`m;t#`~?AMlXxm(9aI`B(4?=#gz53<^QD)z%up&(+^Xf!G=z zsM9v7WA0AfklISYk7f{P1aU zUj!81$+Tj_KgY)C% z5LC%TnDdL173!W?gKERKUi7-i2B!(;i_ygk;_kEQ`W2sob9!yL%O^XFJ&ZR<_G;bg z3J>(_Z++;!8wdeVfnS&Vp^PcgzagOBmfeiZU<{1a3iQ4c-vJ%1;QC@CTgs1*ujj&BzuI62Kvlqy)```1rAosHalOTi*xxM14XEnv19&(twSXf?8kmqxQ&c?5H#yuCFZP-kfY5D)iaZDXq7XXO$8=no^8?mxH z^o%2Dg`xmJw#tElQa7JtJ>TxjNqKwrmCdb}&wk{*n-rO(+^rlG^u7B~I8vI?^PX?X zbF$MVdPoond>RwTg(D~4GLzK0->%fWGve@+e1jarS&&K|Hq}0JH!QRUuZq)JC^wF> zSnU}zI92bn7*?J}Eio~{(7@rd>1!o$>QI(S*v^cj@3|k=y+8hGK24%L()tOrrrKRB zcs;(S(p=Hge9bBO%~Z=*1ebD#2x2sXrO=uP0A5B%M|g98q%8j1<92Nv=?p+nX~=h8 zt`IZu{vH=v++~Kc&~*C-`rJTK*Do~+Z_EdPHTnUllW|OX$c!|`;NajJjY`b@8ye`e zSymyma;G13Jhy9GSNuXY{9bu1$^z^7*4F~m3zV5WM8V36(P8vO)U(4MMXjyW`=Qt8 zUQ4|=H-&to>;03oZa4?v1l;tPj=grm#q)*Z^c?qkul%yh_Dq`Q^lSkzeJ*dHFq|=VYLC~8|U5yORjS*Z!B(bL<@1>J{tq_}XWnEJgOr^pVZvM_b@!Y-; z&Adbp9=?lRJ+*5(zz@NgLLc-pu%QZM!;~R5I7hV z&^K>PLPb?og1R?9=z@0a82bw@zZS5e9S(ntW{bK~-LyUhWSmM#IM5iu3SraLM*RXr zH?sLn8Gfm=NEpq104(QT@2_7#y-I37;`m1P;ggLEhICe}*Qq9(3<8HUN5G*V91-bf z#)ac)>D4&U2U?~f{1n11PI}pN3^5x%Q!cD<1$m`-(^$REB!Bc^@hLdEh>}{KO*7$n zcoTj}#RD)qlH57Q8tHk=`Wo{M0xEq7!lF5&G-PH-@8l$`5I`UT0-GL^3x|RoBX42} z<<($FbwqoyiD!C6P)W?+4$J>)kLB(Ee18BKVR=g-gNpH{9ud#&iwvuma~ChzW&c*{ zEMFXs5B8JFCF*nI4SIS0T2i=yge6a%}yMz|uE7J9Ln~zBp{#X&m{LGakhLGxmJoL3i4Yk!*n+ zS9kFjp_wVvoc=6(I$cWQu#5BxkqxH}9XM%V%|MP^5G6;ghILYM#z>fYhX45a@SFt= zE+J};4inU(V8FAz7UN_q1apeAKIdh9rHQ42(xz~v#htMgb<24|hDt$jbq#g5fXP;B zT*4oyM;29Tx`a6yxJ)7p`#4js%i)pz%XO;~jPuIr>g7oW%-olPEPD$q2O$|ushu9Z zixrD!|Lc7rO)a~*fU>y}!6Y6jDAs&yR}@|_ZnyoV_GFnfGYZ7p5H^Zgy8LSVOMnR`RO)R^1?I9Bdr#j|n?3kzWe0`F1@chy7cdnW5R^f9bE zYFxBwE)-Sy`q8edv>WZm|`MIYF;j0oJgn>zH&y}eMw+vz2eS^k3J>-C4lWcU8a8BGsXAfovNh*3Q27vSTfybV~C{>xF+tRNH*)dyG2=*L%g7Uz=y zj~3MAFxvNb#wrEaZL8zg7vlibq(HG^m6}bJWeWyhh`PRd@)PyCwUwjx`ess}u4kob zmp6o51_0vIG9Y+F*_+&W;WZ{rH#i-@rbR{Y@6R^!Pu`M-q*f?#q|<1zaSuAKJ@?$n z4jf=rWIv;~lkXbS^8mGkJAW{`f8YY{t<>P;%nj;K8gW5a{LW%jgK?(oRw->6c=PBt zkkN&bvM$dTF{@(IW828U;Xnu!q_>a;9?l%1{$)h7V%lf3PYuc;`* zNlDI*#{@<2u{5=FZzLz)>uI0V6B&EOV~Zb-F%L6#c!--x{@EI%iJ=>(r%%hwIAt(v z@68UJcw=E@+`@Vc$aP}Zn;YkK7k`Bn3jP;d?wnXijrMvv^*r-?c{gN&i{ z_l@enc0@N43KEMFihWw?1%#e8wm^>0+^DFxVKf5r`QITpE2}(GMZ5eq+@>=pY?X?ija>idbqF-!y8|; zywo-dcsXCGy%@Yi`QT{DXmR))E9E7@Hph1lN~zIFuJrb!&&etIEz;LtlOrbPpX2?O za9n5X^t(#gN}8XMZOTb;iYUF|mIHS|K;p6K>y9H3$P47c8Y(?4UBN+rd?|A`fr_`U z%Ane_pZLKNFk<>{Iw(L~*ugQdbXZXdS#hNjASK-bI%H@9fACL@wm+XWyf#0gtgc}7VKIZ+$3vyl6);+qnlbFNksyvf zEB=OeW}ley$hX%!%vk`@eMyao6%d-5a~d&)p(4^M&WZKZiPdNBK@oezB#c%+?-zt; zs^_{!=rY;sA<}p6_mDv#8-4py{wtR%iGpo)2_69QJo)G-8+pU4 zKw(jY)V4q@3Wm`9Hm3g@j#UCwD?sHNNV@Cw7LR&~qTmGF4Y;4hO-+ZTbhYJGYQi6s z;ynrsDZkJNlXKzpGwEim24^4H<~2PQr29)pLd+n&MP;FyL_$Vh$n=5kw|^tAUcLi4 zc@oo>eq`bhS=>|!yI_3E93j*i=eaVIO(ZQaC5Lv&#|NN7Pm4{~soHwMjhd1oc8zuC#dY;-kvDos!Z+DyYn11{=|Biiv zkAx4D4Vg(8l~aSXAiR}*OxgXAlfV>GIxZ|JMN9lo_)d9 z<-&gO^2qsuj5xQsYS2gDc^#VQ37JgF=JYf`P92kgz=tVt4N$oN z<_`!6@C3TW%JBXAcTMB62{DWzG{ErF(x;niNkJytW^!eGupWOY({_0@cThwc40$mB zgyP04nsN~ZPBl~wQ-G$neRYvQdtYwn1F&x7Lv0B>0#b&c>5T%;Vv+foK|%+m^>R*l zZVb7NNN*-BSX$uKwY=QRfZsEK6vJCJQ5s$cZKQpX%0!#f7UiV103^1N&@JC}RhJhf zxyUqhfNY%FL(Z^VKHpSr$5buh*Xuy=vrkK~t&->Eyfn`EM#U5>3DGV0pK8zyc^KNs zpFx@*gr$6wNa&JXNJ+y>$iokM{DO7fBZSkMPCs+X>2$L}L<1f9 z;~^}oQu=HxFM1_hDIziXnGSJM$y1@aj8mWa>V5$GZvVkBVz&QZV0b0kUsfRl6 z%@)rLJAV(~_rEw8EdR@{rHU~P{Q~eXtLw9woAid%;;Hrx9=i$o{1`7F9cd&l(5qgS zfZzg5Y|UHZhWFQP+XC?RU-JeMLiqx=BF%1M7C=Ji#J||~o|b}(OtdcOJqd24-Y-tc zc*15e1h-rYj6FK0Wu=niE&%Yd8>8cynxBT?kem25#;CiivOBn`K&7n;m%a2|J`5SW z8@(oHWk!*^pm_vDSP#^-exUbt)B8~ky(YiU4*{aWhV4K##`$(@dlj)Q*2D;S_?-+)}enQ8Fbw*=nC&sF}O z+YpNicb_wU<8A->OXz;r@e1HVAY1;r7 zfv5?cZ=9(`?;}tz6X=yVNTRqJDgr4HP3}%K?rfhv7;{vs*A7Tl8~UP)9G@shT;? zfj?~2G(n0AiIg(A)z{LPnb7G1Ye`pcmrgSd@XZ^Ud|S2~8OEmH@MbFN787mUQk3Nu zRnUyI4h_BJI9o;D@Q|boBEU->{^zBh_k9U89!Z_;hv?l0@_5DMU34oOEmi6OqIh@5 z$Q)R_mYYb<$wW#B7!Qg9EScev82;J=e$AxVrcUF3s_8-ztEr-aW9m=skdOAk>6-T1Axu0Y|?)&-?bx z0CuhKqH=e4Z#&=X@H(FN1IYNHf!Wn+Fa(z=D_JPIl-tUy?#fOxv%62XmsCB0t1=3r zJgn!cP6W!MRQ&#&9SrjneP@6Sid1?!F3p0IRAOH! z0|91CJ7p!m0;hm9m9-nQ{F@a8f1D~y$eh?x*+T&>yU%rl?w2BGvRMXA-~3tc=y8_x zV3^@f#5(C|g78W$pRZ4j#{RR>_`ANHnze`VA+ek3te^9he*B(&!iwi2+U-8Lm$CZ5 z^iyuTq<+6Q8yxKk7nG(d+*6Moda_So>%Xx8Nahd!9j{Hw08fgH`&b+kCa;>$AS}}Z z6>FB>l{&d((PDvke<6?|BhbLQrfd~VJ>e)!7v{p}m26OeXk=;-=3 zH#u+O1~--z@J0cmTL4LFyE@yx$zuRa?9Z#&u%9Y%C-9|GO0xKV+BdLxH?WW?MMQuM zyNZ{2GxME>RZc_e3m7LARI?;UzqT>)g`KRE{uop-uAKl=1pp->JHpqd!*0S-)gTdJSU3zZQ;4%tWV@@Ae@#b2;V#)7Gj%es>F;Vag zPpx)M6uP6S4oM?t>MvQypfJeuWO<@PpzcSxOSoDl2WJCLqMeeXGNEiBA+bFVe`kWl za=EU5N4CW$Jh=Off41)x0MRPHhsdPLQm3lVlgQ{YZZ&}AoAdP_cCu740v?b8jEP7Q zZ37uUWWu8N&jC)a00RQzB@<4p?#J(K$SyO8s9S zg~tnZIq41QT-o>pBba(;XN`Yf-azKFpXGM8wzzXGmEpSpsa6D}Xr0irhtg-8C2hMc zbDn^#y>gRR2Xd6Zevj~%81pc+?5ZykgxTX_-u;}NFc;;@-TjVR@eCxI`(ry>P2qJw z($uQ9m8K01tDvn$<%Nn3C-XS5atY4P_F;ov3dmZe`!0zBjZ-z^PNh_cMX|Af^$V?Z zVIe9eNGU45O8Nu4i$8q_0S{#Ym1ZRS>O%~Hx^GeC%)=5@7lv0)_?Bjg@)9-!^d$g8 z`_oW!&4mj6tw`K^_o|K@X$Bh2`HuOqsGoFP>$6X09{QF0!l$h8gdTS%yz%V33|H8n z$T)au-Y{jlUIutmow}pt6d&$B#GRcnnr0LI7fRA*<-{HW)}TIcv=fG%N}4LPV<3{s zWPQKp^yCTU%Z+YI=7Yg}=L0bVR}6ZeaB7Rb=b0r_2D?Bu8k~TjD=~4_^A~r9 zlSk2O0S6Fk0zHRR=cxruk9y4Ug2toM6m4-+6gli{nOWn?dT`+c-n6~iX=-1|^jw-_ zztnzpe;~FX$*c@RR=(yrlm^7uO2B-i5I4X4>DD?{0{(@oP>OlQLzSk7i&W^8H#{SG zHeQf;{G)GS$_$FLUW8$CnRV}{fb^|NGKKTsuitUMK!&C}-y8w-!Uc})0@~#24R{tv z9NQdt_OW!+3H_n5Mm>aCRPbdnAhiMBct2^#uSm3hP8oF2OF&i@NEQIt@#( z+l{e&7=rbDs@+3Su>EH10E&81SJ%BVXIns5KRJ}U_Q@`b8{zMv|35sPRa{i<`}K!( zD5aF{p+mYvVkCwkgdwD*r5gkU>24ULyFoexM5H8@Zlpm(R0O01<-ORSdY8QtIrG~EvTvuz&Z>b?~XMBV-54m(LlbO z;ZcF0^ks6zN14dKeR0hkW!kyI&aarRNHW=Ss#f3kN{dF!#ntOl3s88V&SCAaLNpet zb%KZxQG_(b{dB~B^zVzOXe@2CXUgoM?x@#i8cr=9q8__Jd{KfF)-Zb5v8WPDy6j{= zr|Lf6+Iq6uMaVbZxbq-ub<1zja^raPoTuX4yEk?EHB8Q?8SE!^uHsg?eM&lILeyAs z!iA7RGom-HFCq#k-)n<4l2Dl-KmeM8i&jXVH8Nu57+q_gaJv0;zQFFkZL&+e6c89% z9BG$m3+fYN1eq;7wp_#-V6ouQDTU2vh!#sTmj zDI9zeF+cx)aE(&Nc2mQD3KDN#{e!`WsKFEQ_3&_LzSfvxE*9l)P`EQWNh%A}_KoVA zy1sz{-29h+>=)Y-OyAD_IwzqMHwUIr`|c}ax06p2+jQ#}_&+=L7`p(7`~jm88r4Q( zM8)mx?f-6&VY4l}_1A_Tgs4ukjyO3xzBUbCzK1I1>IL`C18q)Ap`7`?*Z_d2I|%iZjbX+@zy+Svn~@AszdUO$*aYt-gJxS2%?Ce315Rt6 zDg_0}{d|A(QU>s9?LRvYeyyE%Q>|YNO8nYpx}nZ6^ZzeTf{_k@Oe^X8i&@-h5i-BV>$A9 zte0*zBtxD10XkR}%=*7db*(uCqN@HfyP;b4!&n$N&nw>bUF`T)Tk+*R9gzCOo z{Q3Kvzu*O?Itzzl2pEh8*?qlxzXZI(Fqk$b*tJ&>#F)Q_v9!WTG0q}JbTsqb#A|o) z8P!(Yg)ParznUYTr{2A3u_d3Q>oK_db-3kEoMLg`aOtUOuQ#PoY(FE8fbO25=m{}y z<@_uacskmBhZ5*QA%BbaGi;>yvu@;yDvjK<&aoXve;zBD!o=_sBA>i*=8J;$QjR zn?E_fIdlKJ_(NDTqU+?XyHCYPxLG-mTaCsX8<(|f^;yCpR>T-@^-j=5e<}LZKMX|( zB;2bXZ?*#uUobT-@o{i)2m-Vl3_ptC?DXm1V=8EK5E2z@TH6gCsmziMyf3} zU~AzEJrrB)B%YiZ8sdQCkZ=4uK+#HVi=?W8aP~kJULRukL!6JTbBEP-$nV<5$&I{n z4)5$XvZZ4rsW@1TU@9P!2TvG6Upa^Cq?V4Yx0ZHH7hxfihCsv=2?=GHF#fb*i}vXH zh`xHi_bJp_ux;@UF0nEeTp?PkH%UwRmxt71oBi8kI{w_T&V_>Y(~h#ZrZ?T~e!tk> ztUoxK$ug@U+Dkrb%k{3)Rg6b)n`>piHoRt(mDCL?{K7I@;Pu~kgno=}Ku{l0k`6*5$by0M?{i5DaVt0zIVg4S?E#Y{p`D z-~#|Pf#1Lp*n#^+HNfl*;(qkfUeE|Q%aJ^Ta=a14=%={|XEFpgdEfS}YGPYz+?PFf zrC8JEILlhNd=!mJ!nn+rrZO)p$9Rct;L@{J+|{SAgc-75^UD5E*eEd~+K6I-#9FT5 ziRf|@<1!1MQHWipqJfdS`2rUhT{0Y2(2Kuyy|=50HV$xQ*Ry8Cb&d`o-tp08!W5!9fdGW8+@V=~5B$GluROaxezY8^(sqDfY2aYqD+sUt%~#wBr{JPi~(z6_YY z1cC(q^~No^p5b9Ac)~)N<-ufz@%Mnc3^2NO8|Lpjb=6hnPBxG5&8x_mg^h~a6P{xK z3cL-cG(@IWV-4V}ZabI<v`mST!n@9sFX1F z5zV?S28{P!w8vOZ#UK0alv1m(r0*ye2NrMz5n@%I+ww;2Jk^o8DV?xu!~+ zlN`J^Fw6$Ha{8|gLJsQQ-j@5j|JZnVq=uqoe%p!t1sVl(N(|;KceOOpU_C+(MphsL zZGw1?LZdPYc>uItK;$ln~{Ocl<3 zeb&AHS(mpUM&<30aV?&Fqr64-Cr_BQu0Bx?V_77pyBp;q8ODg9w&ro9Uh9bkG|T+C#xs^Tb-#;A4ff z2Tg1Xj(ugX#|C_~#cKS|YL5TmaaiEOzw4C2ajSRY&9^`1*UhqzZnHznj+h7tp1#6m zj*6tc!$_N^_jmul%-f)7K^XwF`@uB_lzazSk)#EKozCW!Z1o%uh(AKaG-S_K)GPjc zUu?t)3k$}Co9P~Qcq~Iwtc+Qt@(2p zONV!4s$MD^i!W`F5k6!-s3c=*gtM{=L#m3gN);x5p|Nrxq$Y)^bFC^K6dJkYro#cX zYWz|rFs(l3k5r6wg*hLELuU`@cVlCjAdu1F&7uq~`wes@!*4027gLY~{KLV&ztLp7 z6ESOqyRo?+V{gBgF0Ol7NCr{c!($F-FXe->XHp`{h|9(a2nM5vqD2X?+Y?FpnPK^^ z6+BU>@|iE(&+5m6zU?K^UoSSAJ+9yvdD3Zb#m=04^1VHnN%@OMtM%f$_vOYH|3N32 z*fZ|A=bd#|hBKm%A1;-0xi~&;bE3gy769&e5Ae?bqg5)I>d|@pFv3JYVqXgE)V@I0 z(B?@uUpb>wFntiub(ati^XC80#{+H&9S~vOUw(2;v>V9Bd@R6DP*c}QcRU8 zvkYzri2*tlLr-ADer+zw9w}EAn=~~CA)(YJL;P)QRVnVBZ;!MI3CO&KKd_76hY*v0 zk}dhRgsaUhAWT)0MqJ9E$dahNq*f{A;BG9#BHvm)=%-r)1X-pc(gqU31#k15@-5~R zPA+JOpC@F@iNoa)wgogimov{G9MT%u^NZS?F0J)#Rp~1=0=Cp1dbQ$YE9P)!VjIyO zefTeg>UOo4glHeuBW~Gvt}W3H!{#cl`B6scSCiI!YFw6gsN%u|+0o7pp9S}uJj8HW zdR_|{r?l9uMn(k^-@fwwQZ_v^G`kVNF z)c-}3*g|a#C3ZYIFd}_!X1f;hF~azt7nu10Xa47)eh2_hAPf&&ZV+4ZfAJ#C{u~JD zQt`}l4y|dlzb~?B%I%B6R-2;2*gKleiy_Sg2Y+2`C%xzCsM6&DQIz(LP@;x_OAqh` zz35H?v=2tx>M(Jc)_BM`EGD)uou|nugndLT1c!3GNZ1;Bymo5=-)!l=n>lk&@g)f7 zUdt=)Jc8M@`J48|BQj8#mX@VIPc+t8HalToRJB#^Jw|%RSCRIi*u$UJ_tswlwK5_X ztSPMbbq(N{{q@FPR&d|EBj79PVxMHk4BQpVCrir-?T z6X##EA@vMNaxJ~!eXS+jwZi&K2w`}H8eo*L#-$*1A3{5A|H|VD(h^T~Nwq#ev9|DA zl7DF3QIrBq)#Q>(5sGL^?rVwe7Z_B@*?cnSn{VAnzQ7gFAe0L$CQyeYX~>bYjMCb- z<>>3$OQ~WxlK-9nREmAwgl+RvpxxB+$0p*+E1FP9hS<>>WBOFCFHcfNtb3$XTwPs@ zJ;2n0@vBv-^c`&{kNo4!ToK&B-aGrT5`|%ZapRF-x6li~YQIll|alr$B(hq+ux(PQZKol#JXjA=MX0$e}!| z1{uyAPlo1YLGF@n@0KgPN0ErTF8h2hd8jW?bmC!nLd=NlVNNN^g(;#8KXaWiRQ~;K z-Nhteobk5$ZNK#HEjfmN>whSoU|bW4vkxxR&%i!60b=iI4x4%rM96&t3FF7laU?V- zuFih+V@y~KI9+ZJM`n51M_5DyT^4jfP(EMt<0S6)?N2LS+@Qa4ToDJVY}g&y=nrvJ z+ZbH}(Aq$u1J*?C`Y*gK? zz*Vg1N-!6L7q0=OE>CT-rX;RHB>CTtTUo}9!c|)39Nx1Nt-~$U^$S5SAZk-^1-0){ z3t;6rYj^9Q9X9=BfuU;!%c`LwG=KSqu&7kmdw~XD71h11=!%TCp!v8%HWI65PmvCR z;ISmbp~5oDz8~+ne>BA-`eLw`&G7>?gkA~z->9tdRf;+J_7<&PB|T1%rhRo^c<*Vz z%X6v>zK;Qgna>OaGYo?+TYKNn6?9`N1-mxoxlL06BA)|-UMk$J6+VS|!S;UxJ3-E-M*q3DEQXW?u(lPDhr>z1@B~0m&2IsY?AEmhz#AqRYx)H& z`ktoOr7ia;U`R{jlbzJNED&}|G~uGIWwCnW5gyaKW&*P%szO)N26cQ+r5?~lK%8<= zDTRB{;GY+6rDFA{xM75u6xx9@&ct=_4slpj78l#C(iks-QyHJN@{bweZ;x8fs;Z9? zD{Hwz;}eMt@FU`{_SoR$6k?3e+sJ6E?8rO#6sSejypGgcnG>Oflx0ov$}U{&+{yHF z*%hPN+;ovP*oDEQm9rtcL@;6y+^Y*vhAYuTa}ngKA;PAM?I&TeswCs-4zRjWHr8;+ z)gLemO|&jP80vVXja~gpLCJp5^Pt$!VVj~i?f&7tTbcu{1*#N#*=o|VZ4OGCkEIE1 zpN#|e#@yxk-a4fCI^!wbpU!`cjqzAYL1^UK``NR-K`-gQo6*#HqRpqe zmZD2n)7ORo68-t^+zdou*^w&O^?QD#aPy@moA$58ae^{3*O6x1Y}`_>Y%G8{{$~B< z1F(3z0WGgsmj@GekObn$rle+*?Em;c5Cahs7snr@28#zqb6WHvR3N2465BonVgRtS zQbMvHvpOCHG}srOXoT?Zyg?%EyfyR4>&b#QKS)-tt^xk0?cPk3mkSh%Qcp|rm!y!=#v(j9m9oNXIBv8oGEhQulJ zAZfE<&hWe|MD9?lR9bxZ1UH_0+w(P4b%{6whTHJku7InDjZJb7#cfGyj_y18(EImq zZ`_c-#<&A#hvk~tP(=8K`&pUr3LEn8EAqwlr&l8}zIQ(U2t7GkKlnQmvFG#mM;BwW zr~WPL7mU;5ECg8dU_Zb4J9OvXdWl?0D-hX_RydTLLH42>bZl9Jj;*iwe$!2{l6$I} z6FbCtY%N+kv4948`tLZS{b-O5L%+$97cO7(kM)7Hx{$DN=))Ih%xNQCOXFD6iD959 z2cwES%lG2|+z;j*IzFxmCIPT}gPUDcUw=QV;NG3GA78%$`aHsU#rI+}iVU~6CGxkV zJaBtBUuIP8RC$}bI^}A9mO!Pj5@2ByvfyQ6S;zY(^QpDad8e_fE~%v??4&cZYn=y| zc^XnemXL0`D3-H86-xfe$dN_ahqgh-dRnmES2i>HIFu{cBYk@^ z6S>NP=D@MC!sE47gCn&_FNy}5%m~L&Ys}oZnMFp2VZmXj9&^g>`+}kzn|LI@n1k&z zhxdfd@$sn0amj(a&V&VaUhIS|+}W!_u?Mk4Slrx={Dj5QKM=XIU!&Y(^Z=_ky1Nna zJ6FlyX1X-RHJGDtd;nP-WzPz(7*pM-5e#*`lw z>pDd0A}b-oiXU=Q2TiNNX6`Vbg}n8oKcP&Ey^%|vtQCJ~p1~$FoNc>&vy)p(xg!3J zc4`V~wa&Qkwj87NbggoSK zRPfgGI<33}fcB8<@#VFI`izNxQ(CQ6*)}G0nIN$i4Wh^pkj*5Jl0ot|S%D3CWk z0&5Pt^EJqF4h;+_9@BzV9y2+E0q$w5+QFLywjajeUI9hx7eJMY4EVO3U0=`v*LHGY zA%n{r{3k#kh6Ae~08PorGVew)TVnfz24=a(a5g@u^y=p!?61j?om`4pm6Mbu!|pTdrBGODU`qR^P*WyI%I5*07)!%|E6AlW7SvoeP^oEvgM&$VNhrml+BtGAGY zMkHDVu;Q8*@$dCTqsx3n2}wC))u0gXr^RpR1T*D3XqC4SicPmHz^hFp_5{nm0G3`I8CfF~3YVHxjp|ttT zpr2W$fOBDJ(Kq-<{p`rAA9I08uCE>DzG~o_>d*M<^oxFaqwIWnuuaFNd2DVVcE!`v zx?mOu{HIfv4qqWmgAv9T#|Z6~e$G5G;17NEL4O_H#xXiO$j@zn0sFDbF^G#$GcqbS z8U*xLtLP*Noox?9El*ATC%l8~!&t`ssKYBsw+)ENLIlV)+BT2yiH$Xx8{TtT0Xau% zYU&;^uw(v95CSeqEnWIv@9A!_--#le4!+G!1*Js(j&emfFq%3J!7R*|> zF`hk+zLhT+yW~ltKG~woTcko^;>=MdS#KT*kREjnJjEr5zGw9YmAfTPtt2pJE+`yR z>n?y+kRCOvo|9_(zA;>}1oJ?o9cRnL|ImhHsZ*+}h6pA%d>p2N=?1i;dlqr=%r_^K z!_)AE_kAm@P;heLFA?%A6{CjXTp|HI>HdS2$eOc&n3fVUr7v%Lpq zOLR_B^9R3L%A7jVg!M(1zenphs?ij_d_9S6R$n zwSA7%=LxY@x7CXmg9fu5>|l;p4^xo$HWh1*<(PoS%~1;3yrQ+COeMO=m#^I{n)-!K z;@dXwvS!I?L<^HU-;W>E6Wra$zY~nq=xbzkVM*O!6+7hPxj(`cOqR^mqQU5jO@M3i z<9#WThWiOF5aPY4AS_kWrKugR*r;jiSE@5;h6GJ4Qv6~mV}8;GekG=N@|NZZ^EqLh zXLbWe&H~_F=d|g(8DW?xR3FvFbTOO zC!eN*eJJ7QS+T@|G-4@d!?#+9$>gvPGa5>9@#JKY?IqRrvx$r#Zc44k>7q(Cxf*o@5avwC`(h$S{h zSL+d|vBOnXT|R}6>Tgli=Tbr9_8{EGejx}^eKsf_u`(M|GV-(8JJv9rdu2j3{R8_I zMi*Cyx2=X43u`E%ImTJ?_l)c)5M}6T_A(ysa;Nfn!DG<$k*dvgbV|`eT9%1>PBMG= zAm7pbr_)~cBBek$t8Mi4lsZ2LjpXcw((qCC$pd}9@>NrYabr+R3@0Z`krmidbR&d^ z#GroldFH&U_+4?H^W6-z0dH%-W53uoFV%bb__zSH;SHAHV_V~Yvve+1y4VmC5KM31 zjHGiL<*ooA5vIfp1iVyrG0v9B%gbGAI=Y-v>JJhJz8kOi{5Ep?-RUv3tK&kQl60Oj zFm&^S{`nD;ko0=5s&Y@vWaqC#B(o=YUdC@r0+--?JxC5n`9)gtAYCi_6p{G1_ZHK@ zM9@D^%#7l_+E2Xhk-dE<6!Te(Dzkrs4<8&rK#Qb%!*Qu(+Gwh7imT^fLTs#RXb8$f zm)AQ!USF$j-aLz#;Rh&{x~*=j$W%_AxXL$z6-!*XkmxcGQRdugqDaMR5~gi)(1Iw2 zw$i`JDX$emYDrj&HHZV^U#XH#SYhi~?6blT4(d+Fwz!r4kRCVHP`F3q1WIa&R%*>fLRsPwWpbbKUi+p?6<0Dg_Mf%98nIp3&P~A1j)i z*F5%~r^CyM)x-`vK*V|UDumpe@7+UuU11RMYYP|L`Mx96=L zyY*ONkQ!5J!e`b+{o}_E^LPtTGk`{6L}xHWfHWDvkKj-~g9Zquun)8|h71G&;1C|Y z1$zc2HXsQJ4q_5$Kz)F5>{g8|y8dP!E+H$Sz6@Z*#H=vBGe)Rr;3LAo0de=cqXDCa z6--+)jkGII{WyPka0>9kejqqC0$>V!9)pEmkrrJX%>Rvkhp7I{ZmvZb{YvhxecGa6 zv2Kac>Z8{30Hrqj!sLlwb7goeyKeU#Vse{v=1%T7yKn^BNdq!*i=!Gh%S&W3g*^MC zYTRWunp^?O_jI%{lst#Qlx1(^D=DoFt{xA0o02?N#73<3hn)C18t&xMh!-S@0k6cH zBd}Av-YH;rn9w>K-s&J$GQJ1G7AB$)gEp>&`T&IuxtI2oMUN;#bMtV<~bYH&Ln(y1nE=&h@p{X1M%0&e0i;@g;iH#rjxrh z58s1oLX6@K<`5f0-)~hFTDAHXD`yr%vUxmr<;nqh2Es_H`m;~EkJER$2Fyz4Q&>@> zI|sgW3S0`&!4@!nQ;i_P;K;)g)TvetUITHgWlo&#sBW1!*4_8&SR;B;Hum+|LHN^7 zD|>KO;<=Zk1hWU0)3SpC*l1&xuI84 zNrB7vw1#YI$1Is5X)N&-`g4St9%F;rsWX3wddeI#X-p?OyP!U~hq+dAV&eB3z6>(| z{PXjAALsG>^iJhUYKST{nzowm7MB7c_sE9U_P-;-Z}q2vZp-A-^|hb67SEL^O9-er z6gI}be&$N?w4S{>9n1*L_&wC|-)Mh#_WvX8p5Ae&-<_$&J0zCWm~jxi1Ygcv=Z1l9*H zp*zhGn@@%gaKuG-xQ(zLip^n?_i-Of4uc&y#H4Ig1uemyV-syAuAQMf_Ckbo`XmG= zYF5jDWe(5R!o%obcL_qpUx2h{Dp+822NjT94_H4@-zU-Wj8Hd<0t3l||pp0JA{%+LP~26Ao%HUw0i=#POzB;Y7z zgp7$KThJh93_gnaSy^3S*Y+x20D~eXpBcIBg~Mx2jqH5%y|x%yrHDj zig0A87DBhi`vOaa!#PZtg26MIl~bED&q>HXClV`6JKV(5e6s)ZlDL!FW&Ssk#O^T0 zK_vZ(kAL(73X<}(2_LRM_>W3wSYGj$3TnhgatcZR-2RXuB_Oj9QY78QY@^FToMXR^ zCim?g=t&OG!zY6ykP1yp-=Bj+D(t8u?`S+ss^AmVe`eAqlW1P3>%C5v47+GD+k5-` z2T8sZ<~6xisg}UYI#emV{NgCtSUF}d;?e!X*K(C|OPGl=lT3X^W*wXsu+kQ2s;0W* zeR7u}&L14d6TW`^MFL2JXWy4pjeXVKfWQYnKp>F@D9=R9wFd7yP`sfG7G)p;QXE?w z>U&tZ@So5pK)d`Vvlm3>B)oo;4q0g@SbCg}J^e?%S1H*n`ia+|f%D@7G2aZ*ww$a|m{xx7rg*b9m1npAoE=rgb!u3t_*GC> zK`}px3oEbhM2gFI)`f{8-PckEtqY3BxLhfp>`CQY^B-a^jd z%iNb=7D{n*bG2a-1k^ujka%Gv4y-{5L!nG6f@CxU!jLfUQZEAO~#DGx?^MA9R-6(iGIG=ZF|UR+fa)E6K?VaWdDze2X*0qiC=P5 zZB2Z~&KZXQ7ZZdMz^VqkCU_Bqtn7MFWD0!MK+`19pD?X5m|$o3p%q}EFq39etkKFx zvU|4BQMh6BdY*lXYjl+WX z*`B7XeuO&wFe?$I(XZ*Fnp-@N9_rCZDg6!$$Gu}bORZD52H_E7e5ecw55+2cZDWWa z>cx#XXsI?!sglwy1^bbF6%Q+R#W!Rq(dr8u&j#8Eu(Yr4 zD>l_BA_;64FFvYJU3*;dmIPg;MIrBuhgahC9JBA&Xr#48z$;_;QbU!%UL3$_0{y;d z3K(}x@G24Xv0egbfd}-lMx(M{)|T3V!4MNGsnvfm$5)v3s$y#o+!dhHf=Pb^d`N%; zoEG1grH+pY27w+yOamUMv%r)r=I?>QQ`P>{Q1R_|Q`gEO?1G=RrLNl(pBbz8Yl6J^ z^X?M{(5h!~dAxh^ZvE=Kbo+wD(Twf6Q~a58IbMXhWnZ6;{$BN} zCKL({x1fF=*bNK!tvkIg=!_Nsxh%2Ke#LAaIu=rsP!#@*&(62q!68DwSP}j5`BJBs zb9r+0vQ*EE81CHrsJ2eYt*F}RPn{4G(>beEbql$h zpsBUBZXw`_kOlu%|1_VEi$8>St&1=5*$t=e{XhR)&v7Y9udkD2uBAh2f<}LZY9$sh zfh}NxWT|uPYmQk9gN7FKcnn>OQFSqeaj?y(NDElMc9I@{w*R9bkt!t>Hsp|p(+t^g z`}gV21j&1woN|{0XNT)aGmqsMB-R5&{#;%4QsY?hscvfGH;|{2R?J(phLies%aeMv z3=p#0RDa>LRrFGw@x;X{Wk`h?;KXu$Ftx=E-cyZ#Rf-(572TKJK6V4B998B@S?7AY zeA8<3m|gWdf0Na1>Kq8yCUrrjML<_%i&f#nf)Hn;w0Rkth(7jZ512zyhG0oi8#(T) zDx(vtb=~itsFTUrZYVbx-{h&EPK>V1WIMvxL!$BjBC#&86rMc5v*F*>t0F$I_`Yg^ z+kNM|99QxfG#owMi}M(8bkn~EP{%1sY}Nh8(aW|pS}kUiaHACW-&YyB@z}AD08VO{rqnJa=Eh+l zETXb zt2QVX3lb0r!nN*%w29MJNq&-YwP4Pkz}vVYU-1z$H^fp8E7Ef7sU&;%6f)n}368-E zHP=o$7QhQZIfZLUspR6kDpL-Gd9Fm$g2K*Xw5!r9{HVEPV==xryMI4m^%gInVXDV% z{LBZ{eqJc?ex|VDnn&^qT)n=A=6j4-3nZk`u(M!A{HuQ3;?uLzIx%W2b{O)`lO2&g zS~pWVXG0{&mo%zwJsq|A6v5Q){nK=Ad9CJUtB|Dc>xC_DBAo?84$s-W3}*MfH;0_v z;;iAM4}2C*+e!a>7eZ}U&JMw$4inks9mlQ7tlS}wyb0Vk9@T_+6A^TZ1ZE2U`4tM1 zqQ`i7?t?U#vL!IQ9bw`j3=9l2)rgrY8lAg&Y!5lpkrp5T0<>IJ|1%6$3c6Q74=rWf z2e#We4;hPpDUUz!7ZVm;9ZAzktnj8BPMOap#a=(h7?JWM4S}txCXEIIK=wU~dwPw1 z2ukwZmTWRCoSgWio^&5FDaTss1UP*zNAt+Sf`f@NQ!b^olR3yrz8=`Yl~{0O+E{`Q zAf^oE$1~6}`YO7&1HP)PHo|wYn8RrY@1}RPqs^ zwCZpnlFJ^q)d!7+*|4l&_MUOZI}e{0ORCsVxnl_;e2b)QxkJ#aG8^qqJ5lZ~l&QUq z{Uz8Pv$LM%(bl9zPmIPdnfC%v zwv%0kr4Mt2CKAw`#3FaGo0PlG!5 zw2<*1s_#HUd#hO=00GEZ+2xV!hx-Zl|Iqy&dXL$*qQLZiP~3KXVoVuK)3U2Z><^LI znAZtW(@e=skNW{-7@j-qXU!hE{Y*9*ZRhCN558SJQkY{pzn=}%coZ*mlncV z#F&r*ran)|=DD{w!+f4to`ZK6u6_B$UuVndm(|pns(Y0Dwg1vo?N1_gYUTuk{sjbl z(<#8@c+TJ71gfj6gZK_piWVTvFww5BAScV7VG@doEwA7FI|pNpdA4n;!d+ffor(pC zKntG6EER$YlyZCwD%l`}oJ?Vh2Ra?BxO$86#d80yD~sC%Ywc$IlzJ*E;dBlP(Wi^R1 z1W9PUqmQEL8?8TsGbK_*J#&0_Dvo7hp4>*1exHBu2@8k0v+$!9br(#l2tR%+9&YE! zl3Amw!(R+hR{qIMD(Q=`QTuQ}@$@|R7BBmb$|&vcE)tbL{>B8l&I?5cXI~a!94}i99F4c{EscIYieJHLx}B@`2A? zJURpapsF5Us~$!h_Dc5Ioq+OH@QDMqiwbFFS9X>Uf?*fnsMZ^uF2eL}r?$M$CJ9B- zi8W3iyyG68B#XA=?Rb!in)QzX>N9Al!3Q1Vi~=1y z4W#%tF82ylz@F~XzKIXSOLmw~=SQ}2zhe5huedM>PFR;fBJeyHesB~lv(Ae{5- zH<4_$UScO_gVmd;3Wb~;O9iQoL zuzb$ZmFEjD>ke@-WDOU=w4mn1-pQNiUS2YmD`)ASUJMnF#$ z|07quxJ27F*?Z(dr$??FkEa{Q4ZtakgEv0j-XH`9de<-&`TuK8qyb7f?j|8&squ!3yHOh)^RpQxb2$)CK&~*`sd<+qnxbCB zKK98O&f|wn8y%nM?;n<{K@suM~wbv+n zp%(uH=2W9PX^`uV&MaZKR#SU50^t--e3VtVUDW zC60Q|EyXc}VO$9*7tZoY%ZG+l^*c$b`K$sg4&Fu6qd5%V=v>Zl-|k(f``lkv51&7m zWI7Ab`$A4WB}tu~IlPS7gB2u9@irY~J5oGy>I*?>nHBSBg>G zF`tfNKdZ{ag^}P0R=G}ly7hmZ*9yh155QgP3c1gWq}ui9sBeAqMs8nnycS~jnv#Ge z@hyK4$loixppp&RV#r@z_e$n>T*A2hg;@NseMy zd$p0OCeZuq*Do@HaYw!9MtX4z#k3l${~EoT-qBE&_K$^>mYq2LX~<%RYH?9wz)ncd zc-{j{(^gG=H*JQQ2LbqmCMnNb7~aFAQZXgQAQ0JyalQc!0)`+MngY(@-TXmfM-tD} zIgW)mrDc-$AHTevH7my_tJv;PE1mB&%+&SNZcg|}8f#JNaKY9D{kz=Vb5oUh>vz~S z^B!Ad!j2uQ_=(m6m%>A#P>-KL9%fAxccc3FbZkjuABR z4y6Zql}ZMeq<5OdEqlWHyo=jz{HqaByiZfszjE!k1O(873PdRY5?~VH+gIzLtQWL< zS$>GU+y3u|>(KC5E{xd*DkA8=FvO;Vh%cCOBAIS3hW-mudLPV#xrP|iB8%xrR4x(P zKdRkrF|cs>8%Rnh7(48#n5LFWP8-9H%}h*=)Na%`g~aHeNEz{T;f5m-jA=yaS|n9p z>hF4xzp7%qU(D~$nEtvL?KF`gDOnylAkKEX_!?H^qYC%?-LAXp(JTVn4<>q~M?{1@ zXOrQv2um#skf(1fh(;D}63|O>C9BpXzA+G@K#7YKq9b3^-V3wf(P{5RY-KpS zBfOR`4&usH)ZD(nn-SdufunO!LxtkL`d%btuFnYzfyGy|y-^QMt|@90UiKr;YPM|s zWR6Q7JN$j=>D5%D*%;B6WeKG#zU@8FD&lW2!uPKi{MP56bOk-6IV>X@_quQJTz~KB zc-{{aT_-C^o6WAE%R#xrj!LP zrdx93!}#1FGn}|PmeDUx60dWMV|nVH6K=BRFsZ5+n^HVfm&lb3;zQ!@wBikUJ8EnB z+nfGYhskYBdmE7a%?;;a6C++WHS^3P+uEv{XC^HY#$$3>=-=^*G%5V=3%;+oytFdB zCkaqb+W!_wP!L`?WoLf0^}(RaS7>@))aU1C(1#Jz-zRCDP7G=bfi^%2$Am{PL1|#w zVKSQF34yUU&UsRSv>LneZX8Kg;`s>k+m|kI}M!sTd6y;HXn4WD8b-mRG zZgQe8og)d4;e~5j1WVN)l>~)H8=dPFM^RyJX(lW*RmL!ml5dhE$jM)@SZ8dS3?=77 z-7*)?kfl}e_yKg?Y)0h$?B)Qdpm^`m#x}j-o88=$FJF@uYbfQ4P-&7kUXk!bcEwRq zJsuzGSnCAj-H=<1MCL1LL*s&jrS{naO|R!7751Pky=CaV0?il;M5a1>KvdCa;%FzI zkS&e_so)+@eu#1kae}hs?~B2h`@~6O(^GZZKUqgid^J}xNWy%=i(mweX|QpLR5bat zgx34NDI}*49`C%c+cYV;`r>H&cg}eH#~(S*7vCfD@InJ#4JU?5J-bZ(y|nUN^ZH`4 z@^_4WGC&?KYJ0ut_x@f6{3`(U;xD+$I$pgGAz%p~cnNy7?nUi?K!YPKKs$#@zX3bP zNAZ>;;#@Zhn0v{}9n~FwWvGlmV-Vkf=N0Xu*g&sEiNzbX&O2Szs;2cvj8NCI$gRK^n;dIzx5)V#XYg zdY0`+L?B^p$)T$CTpTIQ^AA~6N4Ps{{KQF*XR3D7S5jWl%YbE`n-gO8 z_RZ777cGBItvUuLjIC;)b_t#gfivGvN_`BVdSBuluP5G#{#y$C8!!>$@9N#sdp-PO z?_a>uR$I=>3A&AnS;QVrt%KXb|4hKd5BaC1c17(R{GPPdi#7RL_7K~Z;3UP!#KgoQ zaJbtWfQ;QsXG{dDJ0fkeBFuT^>%l=k_{IY8gbQ*zH1DT}?{_b)cqPx0SzIR&G)}_v z^?1VY`0z;U6b8tYaGT_wD6JBFfR0hHk2UcDs(o9(H8HA`o@mPc2mAqJpNOf;wCl_BYv`9dfv$gJEU3XsqmCLTionKHOkg_j3ej7b96qKj6186$bj``&glWFAoybqf zap@!gqj}7pU3KiDw3+ocKk`sk=!eq4#1Ul8W@a$!H{B=TI0f7L-06KYO&Sy1)b|&( zTraqG=ppty!e2_e#*%sGqKSG$xwu#=XLSh@)NUhpcAm4@cMGs%^Py7J!$LhnpP3yC zX%lW<(a-Tb9@Vsy%J&t>-4Lb;5*DqtEf>98J>1Sf(_q!y!4ytS?_hpO9)ni;b<=#l zr=4oOm(FzYV&dL<|3jIx_|NCnAFE#n;#6yK6>2fdqaXyLli$nBN3ygf%GPFAXHxyg zwbewj_oY@vrtR&OX&ZBJxwXHu9d~GHQfRKW-sUX5I2jTV zkvNb39NecInWvMU#mM**T$ZJ`KJTwq9hU~1Re3$>Kj{ZEW%ji*WxB1{eK%cTPgC9Q z^!Ykp+xJt%&QDNFxY)V2#Nckswm~Us8qG-1YFI?QdP34bo@v$Yb*hPUSbA@(8iH2# zV!$mYu7ZcDtHIwfb_H#zUnSf*Uj8%rDC?Oxi80f-&BMr1_%l>7n`3`N)XJNkm-}yC z2F~0xG$I3ktwesYvwAC}wZTP#3t%mgVGbE^VJq@7{er>DvuQ#8A>s)oraPfe!jM=T{jS zQXV_d`mSTbzkmO_kL*O9(sj<9uUF>OQYo&E&V2Rp7<{S!#!Oi|y4Bq7;h>O|Pn+}1 z!otvD(7qaI2XB6UxF!H$R5DX6$i=NjA;FUV{`|#zl`37!_3psy<@&$0n7xgHDzBnrrFS{SIZ$JT`c5!qdNpST32zxuI`+Sg{)jOOLQPfDUTE^)1r)%hy#=Q!T z09n~oF*0Tz56N)bv83L-OP5cdi_71Wrb8Z_ED+w|*UI*Pcb87Zh0)!eUiIx=^Ce-? z3DF)ksMYnN6E{b_{bw{R&8N``2aYznA$ZwN+{WH$U7^bzG2pGp^;5h|Lk@wytD#c# zYuVxGy6j8b8xhwx@zEYZBbV)mynXv22eFecd*YiwU!rM!kWJMzgX3|D%lY@iD`Uu9 zb;S%f%b%-U>Ubn~_?}~6U>(1v#_XQBehrCROXFV{M})H+s06r))8#qsushO5?vs+n zoCa&bVoe`M2a34+)XZ7>`DNkUy8UY>?Qv5>Ll5vgNA^xI=@Z@$t+UJ#8)?>iH_6SO zQUd&$#vYVb<{kwwt~<2>(|#EqRRujK;N%Lx(S`2r+JIJ^S2ned|9nd#I;hZ}kzIi` z=d=^-or|%j!Q%OLF;Ds;mL#dCl3JkgQ|Z* zLraSc$VV2V>x9%QW^fgHm~M`kPIBH~=3tsT`2+-xLA!fiN=nKij;c2+FYBkVPRK$q z`nLRZFgvkvY4q}1!Z^<#iQz>_kJjnZHHS1!DM}9-rPpB3HTp0DzFAN{v;Q;$rOa>Xe#?mbE6nxfK}ebL zJN$A}P{)=$5%5I>FbM@-(w|}|IDZ8efFdwZ5;I~vVN%KwI7ZiJ_QET*}?T4gt>63z{S5xi(kE5%Or}J&&YTB@2n`XM3 z>29We#=*4dj%hYE-8tRkXh(NV=X9H{>E^w?`+WA#*qoj7Joj^5-)vEtO{3|1eDq-ENxl6c*Aq)+ULm zm1o*SHhHT;+2#JLCTH$n(G+AhF{>@Ur_x4a%puMeX0UDc9>Oz&ZJzzl+f@7uVuUe9 zs?xAL)-6WNzkZHz?YG=yF3{ZyW2FIQ(Vx@k6&1{r1-|y>TqCoM#%NhJ1&8$U6S5ZP z0t$oZB5ZacelcoemtLvNBF$yrX9dvk9(r(`gM=m3QZuFU`LTwEtV{+De6u>#a>B4Q z3cQXl{Wo#v*IE81^PL?tuGeDkwDOjbWCFkd2pDruvT=(L;Udx|RQS@RG85>Sx5ZW1QVe zk|Aa$4)+r-#*&iNJO{m*|SUh*zJ)cmgpep9sZqVyjk|f4a`C7U=z4;~KFt}R-#eQ*!{h~G!N2(Fbl+PE- z;_7MTD%xrg~4}@499W4b@ z_((yA|B0bgnA>!pf}fb*imy@PPp75T=|}N{++E-YoK7~J>w4n}qS8R6T)yNiBr_Zh zO}tCaN#)SB!g}DZlT%fOKRrqdsA|2(4soE#jTAkeB4^q7E( z6o@f%1u1#GcFLid!8$EUYB$!8Jfa^}8&$)HqUDm&7ROi141{JvINA&e*N;~qM8a3( zx%>xQgiK6Kz@7jC(MHdvNmfvYE+2=^5Y*^P_OHbeQ1Fp7_L)#Why<(KQ^0 z_d#qw(qRi3Xg~j;RriVRmJxG6vmu;YMcv4P2y!yU#`D)$PE^d3(wVYM`+k=+n28ZS zGJ!K;)2p@L>6BkWv&P4mm>JP6x`wzw_e}D#_o2*&ps;1!uvU!_KBt(?N5h4eJw}mg z9R(USv+T=J)1l>Fg*{_gFXa11)>Plh3OULW=(d{Y=i`i|baJO^BB37XnGQ3Q_u0=JcOb z9<~$}+5bQerthhylXKtn(Dp(G508e}Upf|1jCe8TAy!zcXVY!|!qU<5r)wpy>(&WM zVg(U4RrYLDT~zpO7ERCxW%yVRAISs5M#axp%OoQv_G-~!co>D*9HYJ2tPgPIRB@t( z-qf8fYcTXIE)tiw-ZCV}zo4g%+*oa70mC#H$w0`K7|v>~5TSh5-BC9CHR`7xzDaz1 zD~f<9mX{(9?(9%Gud)GWjXY8zq;f!74Wqiq!DVZ~KXpkN}+hsMS|65%knEzgd#q(`a z_shHJL1#~i7lu>8$3)1*bJL}oSX!YZH4?|=$sg4zkrVhk+9fwg64KNyb{MtRh=%Uo z2X$9Mwd`9U{|yb-S=@;&N+tbt({pz*WG>REk+_u4uFYwSH@2qh0-vU}tO^Ud?u^&U zzpSp6$6BA4N7c#tFPV{QBK7_~z#+@8y8oI?WmTNf8i@HV890v}U#S{W`XZ0~A8y=C zLNE2w%*<7=+JKB5*XE^d+=7$#wj8iA!SH-gz2c+~AYC_%wb)!Ne=8+M{MQ_BHw-P* zB@cd~4?@MW0{uLe+PV-y?&NVn#*w`R>t$1cXZ;~FpE4TEobjnYCBX=|O85qS-sakdr zrD!VKsEPnCv>!qQqwB|esFzpfW%wc$226W35N0rKV~gC|FZw4aCbiN3Yf!Sk6hk_E zv?n(|Y%`whBSVG@B_&jJoBXJknsW`Ku?xs->}5#c@J4xhTzT>&ARu^#^`7&j>OC$P zA~(8CYd+rvo9z2?=?4O(hnZ=9za>GDdPQ=?WYQ^V;py|OkMm|5|r2-#665F~Ax8yxJ477-T z_PH@F(`|TFEfcu`^k~l+QJz;vrdhgX?xqQG$C(COogWaOV-x6MFA$h8@MAEkB5va8 zc~JLZvpHnjiA?<_)!NIxPu_x~8=z)v4}l|Q^4eo{OS)bBs;2p=ChA1`>F6(X=?9Ix zGd%Iqg(K~+_qU5wo^yt5GsoiLNb~CI>RuqkFzb)y3COeVrG`<7%Ja9Qh*hvS<d4C zFEK9_uOK`6Q|?I)Y5Ko9{$=4R$$b0L6%crM9INsbDsC_NiO&uRJ@@2C&L>eejvY!< zJnIq%y&r7-7gIz&qYWGf<5RT+>N5*|;d5;}-Y_n0``!3Ih5>=>Wtg0kL-mH?MoL;> zwVOgW+d|yKk0416T7b3Gs?d39qq0v6Y`|=keMc%ywJsCP^ZzxI@5xVzw_h}DeJb2O zpFnXrJb3%2=VW|HA4Bm?W{5%&VX6%YJoUJ3$-s}vKO&1-OFZr4y_XW!iKa`SySGh) zB}u;@#9pJ>eddj|x!0(Z{c^sQX4i{g-RA&=QlL&7yz@H($M)+>xnFItV@9$n!;Ait zt*ID;WU(8_S-hW(ge2pNXsb9kk=Udt2Ia~`Q3e>YSz4-y*~y4b|6HAF4T`+P_BnHd3V?sMskT;XKRf(>!sk2eoH4=p5C z<6mU3iEKXh9Z>UDGVdUqq0bBB-618K`i0_ABEL~3(96nF!(ua={xvB`)A@&!DZjX# zchhVKL3*s;Jr@h{p+HFJCed{P4qkzSTt`sda=?65&tb706vQEq+7%*7dv0{QnS31ai<$h5Xl6DiXHt+EBySMj^FA84HaieF_qCQi7)SZ84Z0EI=N$w9KZNJyoDHRkHO2IFS<2Rjf zc_5@L1IXgyKrNlm2ColdzJ@N(UInGIMFiz4iTnF^nR#P+{E2=k6DcP`vFwqroxlA1 znn9EP5{s&9C$fFUA%UKuR%7q&!hYm>s_6HZlz-C4*QBWPUHW*uyemxH*tufJa19HS zs9!{wwI4KhR`QF|p@qURQPBNW%bR5BLi}dk>+CXT*qX8tV(*3dHKlRds9~Mcp?Ks6 zCwF3ru>ZHY7cXF;5}`I{!~q-amROO^GdU0pduz_4Nal^KUD4v%ejVz_76>+<`)Abw zm+JrgT+^py92*wfsD}ubD!DH(B8@i_Cg!oZS_{L|c)y8eCrp=WG{5gtcDE}Vb$GO2 z$RN2{!4#1k9J|q>SDM5StCOaCQ8@A+&-|6|E2OSoocnxusRz(wo(T*mE8r3*n}HN6 zE^C2)(%amA^`IS63G7U#eqO%i z<8PJS-}rT*a|^6TB_$=#J!H@Qwa?+`P;QVoN}aC!{`JdI@wZQT?`0yNMOq+Vlm)n? zpWBHq@ zDhHFo)e7Wh+ap)uu&>qTn)u<~4#-c>(i(J+$OIy*-!~ifL@l@(4b?9z9rq#qT^I38 zi2%?NxPL!_rNqF1+}e`|BQ~5O240M6fB=_n!VM1DXQJ^Zk+*(4p$HpWJLt@N<5oqT ztL-7C={9&iKYDy|aU-`I-PlH3%-lFveF1F_;E;RRA`D>$%8LTt6$Ttwb(6VvCcQKBT~(5oE4rH)5hq&<0^5 zwrX;Fn>lVDeiJ+XZF1|CPeP?>c;+uI61OshVx8q(xseEAih)@pJ6>B!&GlnADM<|Z zzw@k#XDD{zCjJ>@Stn=wURkVsA@2Hpt3n1rAv9SpP3PR=&x?HByfFC+L2>c`DVqES zo^q`+B*90&2)rO}b;ICvQ~pWRcpedTHlf`1L&J#hPpQ#rmZCNDBX-M8qrRM(wZ~`P z5&NmO?0r19`6`Xn^BKQL1oWPs@^uZpA1Aw>Zv4ITeK|B-<*}FJ+?h6YJ&po-n~Q&M z?77w<-ktisw)YNnwWf&YkU75TjU^}i?ewOkjf9RTYaH3BrgF(74kT}efpw$}jJZA% zsN?0i1i{_!@6!|ga+Kr2NCY>3c-e>n6ggwdbZ(6Ez@uBN@k@smZ{>V9CJ_~Z!ni>8 zo+<5a(Zq>3xVV`9xjAURQMbX7`Y2C6a>iq5GU8lgKXAn-dc)~GjrGGB<1`yhT^(a% zSWKu^YbUL%FaV|;w4oAP0_&wckg!Re-SqQT7G4+(xuLil&?!I@2d{jc+W84gO6el zW>dv!b!*d@1Id^N-fnal(=ITT5oVF+_uDCa(d{CjPB=v%wE23?0&sYSe6h+^SB{-^ z0xu=TDIPS;WWEn;4nArzqcrV5W#{qCaR?G?>S5&WdlbR(RzGWO24_9YZ3Zkg&0{s7 z^sP^3epYS*RWdOQVmKk1B|m0tTdrpxY&}iJyfq=>3yC=LL<&ghbW0;(C1uRxJPFjF zzo&IO+`X$^gHK^e3Lt%FA9OsQ?s>2nn82!^IRjm2nQ{#e>nJ2Uewu;34|7I+U&Di( z4zXemz>5fS+r3Fjd>pro*y=s4>matV-nTB>e-szaeEI_N*7-UxA7p!Z#A-8zpKV6e*)BeST%~Wzll|-3nDNflh*;3EpD3&~q zow_7`BRK@ekhpgDo~sWSTUvu%ChHfk2nEpX{F16x} zo;5r}_>4yW%d10tJaif}DVpC7qfz{a;Ya2^s_bp3-#5qZIl|pl<$?Y4pJ0?LQ4q44 z0B?i|>FM{1p9NT}Y7k22^U~s;Yx74iFAaEC&(fxge~uo_Az8S$H{m<$7I}<P8I8wC_uB9E88}~0nq(-F{)b3UjV<^OPC`Ng4A9ZuDtd75wON`}yJfvTU(0!t z?sAu^@cOZBaq_N^;Buh1q*$j%;gqIx@Q;&Dn{%l!fZm>}ni>hz0`HOcHH!TZ}80qO|cdV-%I5i3XjOZ`gobG218X z{jpW+6OC?zS&S>QZeOT&)H26^Lm9iajC33EHmg$Aht&`Z6+2``#qAubY&yv_DVEA-IKY(zd|)Z zutoAuo|H)x*Fv}a$#VsZy(*j0uNd_BsYaH})(S=bJ`D}Cg+F7&vK3y~TL(kdQSrIyz}t zyMDR3{G!Y)rX~HjY0lI3?{+nE9+hOvxcKUw&nLGT{UGLaWlnbXj?+_)t7T7C5a~F~ zzU)}4CEzTA#`t}t0W)b~Hc^{);2r# zgq`=k4w%5B9f=(qm;k=`HKPyEKXA2>gr1(B*(N$dz>hq`jzA2$1+81o(PcRsY`Y&k zxuf*Mvr)xVoLZaqw2hzO(pkz<30N{4UogRp?kwd}Fpv`)sKxE1yfLFNA;zU-9;cR! zQFRVsTkSma`t^q(q996q;?mGdGMVS=Qor#TVl^9zf2dgB1jFjQiSB~mpR$LU*{UuG zxAzV!E(F)l=ABYpwDc?qyNthG>-%0O2q)(Z8fN0!W4Cq2o*=mtiQRjN-eh+7#f)+b zPr`*nB>$Z8Z)czI@^z6ky$K_bf#Cy+2$Eyxbdlq!rGrD-6WLTrdLslw%PQ%RJEjzg| z{_>5JsATP#0vdX~b15$Tv~ra+Xve_&z?;|Z!6pKl`gT6M9?!k!v0EN`=G6e)SY2Ih zD1S2y|6@AUwMi*={MiN8$a3hK=Fy_u@>$=ht8E8+J(As8X3is8 z-`|YpG1lz3t|8l72aDY1ifjSnCC7zFx;(Vk9}(pp5mD}vE$4?178#3f2Y;U%0ULBj zO8tbGfD3J7<)O*9Z+EhA4xla1ZP*PUlem;QbRZ)JRp18lHyF=55m0mA$~N%!7Zc-- ze(McId`$7P-O2JUKWj_FwWrfy zqeF?6)$z!p?_0V&GCC5ZwR_wcoCV_M346<&#_`stI2vkjaDTCTEshCV)}E;1h98%B z9LYtUDvB-=a|pBrXs6B{AQHy)4T1u$2mfzd1O=wvR&Y9cWDSU7FscG=HB2(KwD6 zMr$#*+y9y&d<@6I7V7R>pT!8oXQ|9>7&TH@Z^+-V$e8kz_||Qwc!wj6TqLgVVdkkL zdlijI2@tB_3mNM4IvNzAdcQF4p0#F}pts<^pzLJ@{Vq+f^Q>kCdUnH7)r7;1(G0Af-in-1gEN~hOi5ToVNMx973 z!;g^?RvbZ*{eF7NTLv`IwTEXUu3 zFX2YKyHpN5+U^}tVq&iQ?D=56-xHDG@cqMWN%JPKx{DCMefxExf9uH|gS~>c{DN}> za!jN_xowG~eLq02IocL{>P~sw*9xp0T`h(bsz9pi>t$O$w;BF=7!?pj*myW!{f^B6;&?30re?!}ZaH(HSTLs{0C5Cs*fr^A3iNB{&kK-a+ zNj|$tbV-A{&0k|08s_S|7Z*s92hA*MA;)-U>L^%CoTVE!q>KbB-CShClTcRq516fhhWYJ}ncH+R>X(D)9T1(NwfW$%5 z3MSl0fBMn!ptUM^%M81%XyYF&5C7rNr7NRRiz55)q7!uP#L}?v@HrHWoc=1;)2XVT zx<9Jq?C6GW?F-#;w#7PbhTxdz=j@A*ThhnBBlC||)cti2BeSkKwquj=l^O-91h=)~ z6i*)!Ey#)(XVd?9xV05TPg8QZgh@tqlIDGQ@V4A!Kiyb3@y<+1c?TpGAk$?N6tZsw zzWGd^Ia;ob`i6i2cw)2?dsbIhZK_f91gsXWTgix)FFcMGLtEuipd@tkT;y@JYvrm{I0X;%G*J@4Aj-u@k-(x*2L}d)kZ)#Hu zBwYvYpgJ^&;d7^m6?menP@+`?u!kv67uOt#K`4r9n8KX-m3YzsYU6ZsYP#%oru3Yc z0fExMZ2DG8JmI{-y!T}^V{>8Uktg$J=*u-|4H}r3cvYyJ9_pfqOQ#rAA?+tgkN+K{ zDl?D1#S3y3N9Kz*iRO3GmNw-gd65D2ev67AmAkv*+flsZAiZQ$dm{ zL3k-!U2iEGFhQ~TceLdXK!m3Zzx8|su%~AQi%2!4&@at~{I*Ea2fstdz1q7*L0Ha1L|2y%tF<)A7OP87SGPPph{ICCd zLiyaxesj3;X!Cgf@hKiGwx)9qKaj_}q62(c6Xcsg&){HJeFm*Wj+p(C*r4E<*S_xA{CZ zj_|kaiW)dYW0IAK(}|zBVEFu;fwT-`ByVh?CSGM+Z2TsM3miP6&LlB#DcuI|Euv@5 zEz5MTb_au)QePV3Ej5Wkr(Z1apsAJR&0(s@8_Jj^WSh| zIrg734wPq&VL0THgopaZn~SO%v%?zYGZtKgKvL%j?naIj#ZQHC)4f*tpUa&90s^iA zaFl}?Yvm*-g$cj3PGv=I|9W_(PB?@C4}BJ<#505#LhwCHM&<6T4GoN^cC9xw;PL=Z z1`DNkm37c3+69>JhSS_1n>>MV)g*u8&fKD_`aqn@i`CX%iax1opSzC^wxI*>gE^-ytHBBHAQpoUk(vHO0*u&ZcFW zH=&rr3{O*)8dz_cTFf$b?b(7+;^D2)HL@h6OLMIzMH%od`g8UN{fc1a?@_Fnk$`aX zsedS^Y;li&u1(;HXyEIAfvz?|DQDlW=W%RUi&}hPw{141i6ZGXT@-h;%^+^PNQLfx z-z)oHIpM^zUJdtEQtdKto|JD;+4PtWOBzR*{)aHxh*$=!pxw!>UHZ(?NoyW32hXSS z*!DRjXJpU-#sp*u;ZTmGHmdu@>xR7dI~B8p#LjE=RPd@y}i&uhaZ+d5BU_8Kd=2BchmZ;3x?0t#>gA*Iql||Nt=tvY*TGe zRVe_M6VHmqqjW#By^Cv{X%1(^uhx} z%X3mzdWcG4xc9VcZTwEnn$Sg}w=cfc^1_dN2em3m6JgmyKTe5Oax>;k164PWE5+8J z`-A^Br&gktTHG-I`R3tB@oPg{9SIlq&?FjfWqr)wrnws*{U!sjq<~V4SkQT_!$GPU z8!n?a!AN?zva&V=RR z&6pACKc2m@dOGX<)zCrwut{o8?{;x<@el=|)pE~?n{O}H*Q%yJhBLzAYh<-mo6bml zK*0(B$s4YuEn^dW7gIoQL;<^n>jym<9hNTx++cwNp~`8Xcz)LYU*wnzWx9Y7*HKNk zs{ovJ%klkbQrpnf6yEbr{!#D*3E<;f^rx(b?n?6gdwUGvFIz7)CU^;xRh#TbTzTkO z%f0R;dm&oJdiz;~@~a>HPONB?#r30#Y2AkAgbX;etJ(V3pWTn3wgcc58a9+$2<*|U}A zUz5LTtQ2L(tcE4C<}YRlg$`blpT}&s?3GF9mk4CKBp3L!$5@hOJ1T_0=}^rDzxOM= zMhE%-sZWQ>n*~vDWDUORrC2~({zgqbho}2<`X}FH&Y$T#wSs1X9a(lWXYm-{Sk$@V zlpDB(T|aeJ4Kf8Ze;#VSe6A9g*#@at`F8|L`;p_u8uAhM8D*m=t3ikV7??);sp2d! z8F{0`X_&=hVA2-&GSQL%K$l}+!bZ;K_$)7$HT3v?Oii933BpPuyhhUW=fY`JFJ-h) zt%?b0J{I}BxI%*2(h)O$eX3!g4RoCGwvX%2E1|N-0xh;3D25468{V?Bu=qmymUWkw zmwQ%QlX8QqXIcdB&5K_hdktOJP#V;CD|9Hx$g^#}A^_*8q@i?2tYr#&O{)x~a$o;- zplIvqwQQ7?FDw5{V=fTEG-!xn6G$885E6RkSw<_3`|S02U*i5J|B#O)3kbONZZr_< zG1ugFOyZ|Ku5SB!Kl1P}e#6!!GWXT|Ja1_i;e}s@iFw7&T;a%PTF2(b>u{6U@JOjO zdAGawQfIX@3KJD&E#}H@$5z;#gWG2y8>#j2qTC69>p+U~Z0vJ#asmNAHValihvNVN zZe!eI%~<0VxLwSR`<|g$gp1H7Q8TrsWe1*W$H*!UQ&r6g>06DJDwBz9(@Ssa-(RG5 zC~eS{eGCY8>bZ&y^ARE$E7oK470Kr-?#)_XsGy?Vgs=W}AI|URq3mbKVN2lyo=mU-+6Zu)8 zQ{i)4TsRA}Nkb(V$*z6!Usb2zM5;YAxAIebV!JSlv#gb8NdjGpAb@P9OmE-FC?{e|BGa zgUE_LK->W7f0kwm(8Wv(T9+E$NTP_+VSUbuuF}~DlK4NCVU2H`nwRsT_*BwmzV8JwvBZJM_sR_znHWnbAkgEO~eUvx9XvbQMl809Dr!k3D z1kyJ%A|Tj1SV&-}=3h!-9fpMpOyLBrxo?C}X72B_7^!+uRYZ{tu8n&#>!J|Ppkq;C zovou}b;iygd|OYbQ&RBav6^MXP5kWg)q5&6R7i(Q0QPoLYLLK0jYrJj_V17&$LcR# z$IcUc!@`W+Wvf~&%p~y%^XoX)X4riu^C#yAvzgIgFr6*bHT{bcpOnWHs@GDRu>6i$ zxbS1LZUrsnkNE$Khbl%bWO?XxEk3h1p$XI%?11sNeZZEXQ+sRtub zYVJ=_F~uF&a6c@V>W21uK53s)Gb&|jyu|=VLj$Nm2edb_uooXsaJa2)zS<8U01eE} zrg(nGfj&ElRlh)mZgEbs>X5}QpO4KU{h*jEft%xFxG(^741h%j$h~KoJ;88ST2`i3 zK4Z*wa<;gf$@Cv25u{H4| zcZW^KlqjF`TmZr7uj)Sz`u^B&tS=+t^uo2mcZujBSKDWaajk~_E}(|c??IKVS`Q3; z-e2<4w?+z2R@zKhOnyid#3)gEyYnVFYbxY|-Qf4xf2E$5FuXX{G5FscC>FPl4tkcS7U^9|i)R}()>n#}%b!|ukJE_csNwtOf zi_mPJ*H!y>y@m9s<6+}8#a~~39OY{Du#g{K+S{9}WxgXqew%`$v+!ybmN$+m){4Wm z*Rgq}%-ssBjJE~5c*+22+r-KWcxJF%>8K5K*jJAE{S*8M_naa)2y<}quGvq`az&t3cvL0$+bd0PM z_)<&KpeIDhY=Q5*C1c8O=RUH4Q7X(`o_*D16M%vD6TzbT>W4UkMhN{iA` zfuW?G@i#7cog_GKp5|_R;&=(X-DVjAAZe2Yxugxtwv9(sCTic$0q@j`X9@T*7~jm@it(i@4{nTlb7S;*QSytrY142@n+IIq1Wj=R06bPME(o-u-8R zPAX*1&Sf54kb-=m`O7Dn+H9G(DXYOAf5H}ZPn^Q>G?HBE;P$(X{{#XB*WiC0w8HTP z(Z_rq3KZtBZx!mp2W}<#d>$O_XW>M3iWQ!?){_v`k~#}+D?zXF!GbkB2DWYLO~_hH zR#(lR{Z!GW`*qF-K`*+#MD}4uJMMl{MJzUgMxE5)mk=667H7m6a|CM9uz$Dem{|4o zk%rMZrv>rfTo-n-P~jK*oy0CX6SjE${t)T02VZJ?9=8>qv+BtdNXp7E*l4ke;Gj~} z;Dv;J`t`I?BBSFAtIVetL-kMaK>VFPy>1^x<|r^{2a5XxQ3aql zjm~`@6cO8a~^vrF0sHhimof?QiAup60=z+uD zusVXE*ZKs02w!aHN#=`Hr|J>bm8%oMa;tDktg!f4wc>6>Y{B-|9|b#}Nm{Ur+1efj zGXyWAS1i9Qnei-(Ta~)<%jP@%o@P=+9ZuZjrbH$GxkUtzMCElZOSKkl&-{73RXZO8 z#<*c>PE{1@pg>HA32nO@^H@~(XfQU}{|7@L^#Ii$&%iMlPd2Q|cv)y~L~-EVp-P@# z|5B!#7DB~~ zYIS@OYNngagip;ck0Y@PGchp7sdJ8aC$r7WzToW4Gup8}w4}TcYOAbzzFroFVTUNs zlGb3O%IhZ}_5U)On;&9pgn@wpno@*s`agoYqZ98HzeEkfLp*@JqZpdnIf-%d2Fk0m ztE)2oabY6R;3xmL7riHehOu%65*2^wESBpv_1>Iq&j>b14+ZQuo(zAmlu@oy&l>zr{`Qh>ID1#aA$2ei5A z5k_PN9!eWfAxMp1OJUd|g@TjH(9j>-dq=|S$SHFJSnOAy0c4O#2jHbh;t%39aShBB z)uePS+FSF(qIQnsANRhW^AoGb*1Y1S&gXA@E&0lNxAsxSS-_SSQD+#Tpi#k?a*LWj z|0k)h|45|*4nI$cuIHok4EL06-3Q-C!Mm$t00|1AQt$!u>87JQ*4w=nWPyD4#^%!4 zvW3bl!Nrfzj!LH6Q;P`;UfTy595c1w$qwp-w;110j$G~4(UjuKEns-9a@1AUYbeRweC)ZlYIk1@a4k6+*+@bs63+CUPM-x2148gsZrM%F_fjCJe}8JT?7 z5y{MQnAo>=HIH{{u<*@8g2GwUH?!M8Qjpba1uoZ2oqg>1ttkGSgsi`*ShbWj6@6YM z<<|#U(PDGE7_}q2x&>c!=XYgT7jeF)F%!O-j!-cRCM?OS?;ovd;>C3{EqrctSZ%<3 zs#tnVBw@du7Vl`6t#VxmDlF~fEf}`sRN|*z3=IuEck`Wr-_=gr%3zMXIRm}*fc917 zIN#Bn5BoUTc!?Om>D&dY-FeirVobCQm9IALCP3=lVj9cxin=`|4jexO^bEiZK9%XN z%~l!{3%G`hXWMu6aB34+)h*O49JoMl?tDx1$=Ga)LeYaGoe2+({?A>-mm>f zkr)@is4C+M?#ewj%q1#SnI9yGx%HUSA5_#4R8ehovjmtl@scQ-NSeA5lxc^t*xLur zgc6gQydQF|W0dhiZ_Ytx&DPe|_54h0@0-?tFEZS>-T_BddCMgsP>P?_#x~ndbI7Mx zMx0Cbi|R}!+KGN-NkV@|IOh^+JRGm#@TX$JPofFyt%{*!2wr!C3C%~Paoeui7xu48 zzRR;s>&;Y5pruhO<(9oAiPcJUR|+f}^`AiU={8FF8fE1aYAsJ2aFz;b5v$%cT!`&( zd^rfyE^41v#jTd!S{uF=zwxI`i?JqDQe^>`RkRX@VseS}i?L4?H?^aQ#oTYMr?Da7 zn2c5Q^=!qmg@Ts{Y*|&ByqYhd1!g{Sm0yDY(057oMneLmqs{7CcocOt#m(|wA^;lb zF?{;At>lm8lbqwvBT)UG6YX{xY@i{zZriokBP{nbb@u;ArATlZj*&W$2nB<^#ZH0# z&O=P~`0k6D+4X|&ot+cNuZ~kL+&I4m6eH;Ddagv7fbA~0uwsP08GA$s8Jd^EGXEOd zlWIimbNdPjLKGEcpMpB?afAj zqnztJXq{kWWPG;Hf?(Tqchcvl8W{J%AFRY%1qXe7dbsM}blitiHJWTTS@52?+mYta zNwer^^nXJD^qMT;nsnSf#*I+?dBci0@j2Mg%X zrDWeHh6FyJdp>~nJtxAwz-n*B=3#BxV0@cQ4F5O~S&AcAinVoc=_sS-lB7uKuRp&O|k90+;Hl00b-Q3-0* z5z-rNk(Y*7m-luI`ISuBBnz@r+^e2`V-Qq|#7_{r=GyVrHuy-N5m8n8wBbihV3oZ~ zG>uqB$D`&QJp=D4Sgi#|-=iWt)8WAA*a;|cU|FnhKnQI4Sm}6=jpJHSJ!a7Sk)TAF zF~UzYO&|lEDf&pV&)ML0Ou(HG!2IUS@cS1*e)!rvN602EYEbthX%QJR;qeuK^^tvCX2nqf- z>I(*?hIsq>mtCer!y*1WzAR8@`ktXLL5L>Qi=+9}jasb*C}6NR;aqyT3rYJLRi8&= z;Qk+bH51*om*oWkR5MMNM~Wt$dq$Mb`DKkkADziWz|m4r!-@B#GAs384j%K4iyNNe z_$)1FBYkFytk2l>982pvcP>tXukvcf2sz&IIqfdlE9JyqJT4#)V8$s4r`&BP1@h2rI4m)>Ofbn-e!Mw1!e zXHzhfXbQh>ZYDKcWq7*ptOYkXuOVUifD9KP5ypdw z%uLM8ssN3kp=*q}YXv${GY~oePRuHoeNFJ72XRp#`vcq|#eCM)b@x?`jq*Hcn;T?L ze9uJ{;Hw4uibQW}#C#K)biT}GwhVdB;7w+bzn`%?u44)VDq?^@f_)iC5TEx5aEm;@ zl4sx)D2hPOSuN@VmuSqc=$Uwz(D)0UIDU|d3T|P#eDJXN=(YYDWLi^y{(5#J2!tbG z7XcY2?x5A~db+MvN?(74#3FL~jC#)`3pz^mPIZrjxSgIH;H@MG#WG( zb|*2!BSN%N zgCmM0^SkDCo$oO)6a?=MoSskU9AM>YdGmSobaU{To&ht_)D#z>wkhM3`}p&hlQVz? zsmgSa;91c8?5%G(pGZZCyXdX2`$0bOlt0NrFGFK1zLf4)ARuBA=km6P0&^A0!~Id{ zZ*>3fSpqS7t>UkIiCjw%c->~g3dkQmSJW)U@v=LwKwv*oMp^Ad7qqYI8iCq=qRp75 zNtLw7{r*av&7pszGoL2H712LuHVK5*5ScNVq;t`{b$xo-F|EYmS_EUZcuT!f|0yXf z(xF$gLJjM;DRoLs;IUP~7r_x-bB?whr*o6AeDu5}lloG6RpnuACMJn2Dz`&tKIgh! zHT40Yx4-nsbqFo6Y{_=tt%xe*j{H-6hb#uJRftU;&WEDfAt z<9F4$5e1E>EuWH}CjSsdM3}lE5$kGoAWyvmDuKmaeN>BrO z!U{0qsugPxpQiSkfNV1$Q{n^_0;Y3(H$IkUgG}W^oa*?cJP8gee+Fti8Bo18EQ#op zR%TgX%MWn7USx4+7|o~aLp3RrV7@jC zL@I!;u@ptK;Z~U^DEQH!xCIOm&w8qK<-P+2pq5sltFW430mq?Yr506!Jb-|Yo58Q@PU!KY5#M=_QPC#U*nPA}6y=TIQ;!EIMz!J0+O>o}lO zZntbP|1SbS2Ed%6+vFMnlH2W%Tdo{IpHEP5@CNM#P)>65M`cbCB#bJ`kg+Qy5g#X$ z$mY*Bx-fzPft?%zfvisztKawN-%EX}-vQxrH_wc0QtLT2Xfa8ow&NC>`EX?7sr6CL zjpWOIZL1`&;rD4lnZ@5|Rn?3!WmF?0@;>25el&g!p#}L|PrDnW`ptEUhLbH^Kbgd> zz`yZ-A?L?j)h{L{0gsOyGLfVJ?doPqW)BZfy`)Cia8oatao_8wZ2-?8K7f2b-ReJC zExT`%kb3@x#^^iALSvqS*MQCJZBKD(Xn zEaSp&?rbN<%j&oev3MR!qerKEhg_SA_zg=`_|^p)4_?RDLE!&DaO#R@EJHcpC|&;o zo29;D5K^C5F%^7(kQ7gY+yZ9MqgM-pCZh7VQHQV zldiZH37Z7xd{g3oG<|0v*XeP*@f09sDGpQPOQJG*bDdmk3f;&6ZNY>)_fH+D=|vSRyL z$p0x#oW-l!IFndWD|=P(9=)TpYN;rQjL*hSOurqiue0KVEk}ue@sy{o2Ti61M@C*; z_QLydGoC*!r?=TPjHsFuWG^m;4M$ zNL0k%Uon=to}_BNnxPk31r05bnI3C26o@SDN={>JWI!1};Ba(wG+nolw|8OtUX~H$ z;M&w7Yn0ijL=t-0qh?UxO!9Hepi;V0V-121QlGmMl=8yxz5(IC2r=u5;?0^OKhWgB z)lrRqaQ|AE(kT5U{lG&Q{ys5K(U62oa-*QP3g*B6nmbjqZMi^pG9* zA-4sk$kO=a9JCF+KoGST9_i4uDsnk$+5qGLx}Q%-wW*Bh80~V3^&Cv5boBH< z>9GT=M+bVT^TTD0a=gJpVZi-I-=1jvGHgxCYbc2qiTpp$SNK3(3|VfoUCkD z6hx>Xh9-M&M?n$ zFQUT3wsG+6*C7!TI9W*@(EOUa90&h>%LhQcS~{=E*J+Ns@(ImHMpCIjoljW@DUVdR zt+xk}hy$B+8|F9C&hCZYk4AFNj~wOD-1z0Fco_1iajlAL()hozd5XEVh|NNbrQb3c z%ty&qvVoa}FRN#|t60XiYR2Dh-Y$;oSp*=?dZ`+uS{VRB1%+t9 zqQO^CIfM`~f*%nPr+T#f$oq32g?H-A%zyA0d^))LX~8RUH8cDdVmG1CD^|UnOMBZ; z%RO*mVrt7qG;)L$`zeo_@b3h?Px$wb;(b)?lWUsWaNZr8R%+zFVdxf2r$hr+jj^3w z4BYwWF5ano*Q5Mr+o6I~nQ2^_bg}v#9>OLxP+tT~g#CjRn89Em`Y|{NUfaY0*cl3^ zcGiwAG<-aBq$5u>26^?0HciEXwG=MRhW2NwQGFJg&nn%Xda&!x2?(+Dt zR=)cNw1VFLWa@VbJPTPZM4BGn><1xJEV42hzfNhQmXl3;T7LCeEIi*Fh_U0xefT}XN>;0hsFta+p5p@`2GWZt69-ByJ)@DO`xWH4GaL(3qS5K-sXWv% zaJH(c7iy8$EqkSqx8gqC5vwI%LdALUamID9)>T>{OPSFl1LHru8fmj}@gL-BDWM;m zX;Dub^(n2gMJk+M5PxfWc zT)E6B^Or+%NJIvb?8^bnPArk}Wbfl^f_TA(_qkZO`de&9k$5aqJdYMw8{H$HRNJZ1 z-ki$!b8_M8=qh=fT;1^`mZ+Wqqijwbb(#Y3z_sfQIh~ys(}v1Ib${#=6Bvihk(oGH z?<-?)a!>smw`teD%HUI5e)!?Inina-(YaFNpE~5Lx5L-4Pl1AWqP)BVoP2dl%MSqa z4F-MtMPzZ1??A*>Lz!GAo^Ervx|Sr>VY1`yKcrRX=iR?2$!hNQY#ohTF@vcnh)m>4 zFMaPGq|Z+*u}KP&=tm7IgC~=L#whvI7ji>>fldYxF&Hi3 zAKq_LEzKyCr!37_G+{w1>Xiz=*J!xQBH!JfyxZ)j&oDaL7zFJ&6p$zuy=`>5|1@VG+Bry6`cqi-|NQYc?0lYx}+e6Q8LSrbFm!eBE89(QL{CM+F^P$z8JW}sSJH5k@Lf)7Ww|Ujf zgRR#I{mh9Mi)Xq^X*5zUM}yBQtyAD9yxPPD%MKg7f&3A3ypu|Vrrj-)Ec>;VQySXZ zpVH=Y&LnRo9w{klSpS_pz6T!Q&25)+v4z@^d|Rf_a1|1(qW?-Qzts9v>dSnOKfhC= z*22GAr~DAGL37u;a!w8g(d9}%zn8mj7mA?~sNIiTT&=LKelpAZx#}~8+4e(lx7sE;I2#`>g)t!!NIwjkJadqgXk@!jEJRy$Crter3RgTJFwy@ zqa~={z1fwB6l*i=%v-54406@d^edpKC8nqpqUsjQysJ{iUHZ>Ndr0S)-!(r%SsuXU zI_ucsO*l$uRNb9S9>1gX`b?;DdGy}iN72ZV(EcIOC3L`g{juM&qvs)i6<|7ae2nV} z9wN8z@WXm;!8Gt3H=^g!{m@C~f)hVF#;1hrx}OFtM^!SxlPx$1m&=~h6YTSsFYMoA zq&}c=r_dWOyG9$>n5ZTcxZZdF*F{g}bshcSN>WF;PP}Ms+mz)t@$wuvl;8} zVOggH9`^Lf+tJet4FrT*Puo6NtigEG4{UND5Ch5YYvvpq_ahE9 zEPqjUsw)0^lW62+!jr7KbT$M4(8+$Z(siQc1s=L{fBMc4^7EfrGv zJB}xqbH|dPvKCgTSb9Ze7J?Z-0N|@es2&L3No~?@Jtm0%Le>|usX9*<{8jpg_;g+Q z3Kx}h*Izv`{XC>8-<_j;k7s;F@11KUUo2sk>7KdXTD_>%C+?L9cetnsz9wlPD*WrR90I*Vf# zsZ4Ed?Q3{=uI=tVrE#gePnj|X<7?N0e|dZd3JjN3WK)O16QRiKFOeEkm%1J`=8kjy zyNQ@&nj}GAjkq35VP+}g!RdU9V%MmBZeRWE1Vi|!AvcOU$u0qpp;T-zSKPcNE_hw_ zpw!00=A``rp4+_$E1(d!>HHZs?HX@ED0Eq$^m=1e4DC$nzJ$yqWzwgGW`1L!W{ArN_9X|Gr+y6)v>AlDw_|WKYEpv1H zn`d>)$NC=Eq!KL#r_MhdF^+lqO2@BriT554g=nn$u=;}sDP*GQoyI;C!-fClDAISU6$vT0sGk zg!*T-&+yPKC$&i^{NWaB$5TU5+}sx}s>P}Zfar3o;9}z4HNsf_q@Da+1mh(oZDVFn z>x$r`4fdl=`Z-hVgYn(UL^g%9GN5)m}1r-9O zNc_w?aA>Q{jVOYc{P*=)270GR!PUYl{X(J+YGxKyY!XSzwoA{U8Scrz(ZZzVLF z-Bb*MG%W2;vxmELdt(x0(i5rKCeZZ-C&Yh0%&j$FR!nby@p1KQ5c%unrtE>vEVW06 z!r@VYwyE#lws@X;gwH(0cdc9RyVrNLrA3eC3n&c4NXua(Q>T;D50~8>al^CDm-!8a|I++@66DMv zIw=!Dsb?C1E$}{v^;V%{G@P0Yj%0ctfa3jU@t>2ESLS|Q zVA0Gu9V&`e1<=>)6hsYWZ&gPAN3W+7OTGE-tFu$3#irR$3++}nUKE3VwPoo@2Us}Z zuW4E*oN{dRx^_#&@cz3d({|p&{&!~BE1~&-Z{k~jzYIJW;T>tlIk^%FwbSDb-ILpA z3|a?Vg44sdm)FI3a;{@Vcx)m;!#}D_UvP|>Iws1*d}YA%ZgToK*uz9v?yCJ|y1}WQ zLb01tBJA7m-)4yyd2uno-$Pa#s5W-CIhs_im9)iWxgH*~;`o;^Er*MYk{rIj(?s=`yT3qkLVF3{&`z!qm3vN)AIX=L^2fIV4)& zuT{p+gbLyrOYf-tR>6z!{Y%_`oNA&kV{fjkVvSZ+G(syQ_xPwVr>txm>5EF!n8U=B zg?vZHLd8)!Ws}vEE@e=wni-Tt-0C$Y!)$Dl>rJp z+9xzE#+TlsS=jMEaqYj%s8PA7Wt|HxJz;l0Hh#z-+exba_L5sC)NkGR{P!wWUiPOX zX6)&N;JLFLeb0lp;c_bGp*^p67c=J75|)dkkPW-4at1IqzZ^I_Xq}jRxIryvzg-PK zy@qW-r8qNBxu_k`P;b%1fooXAM4d+xybF?Z%y3#pP3HLE!_I?HP*9sXU(5mw4~(b;z&4mMYRxcQ5pkeFa_$5DJj zDqRk+64+bIpaMQ|D5ej8U9uI#{s>Bvx&1G*@b&RH3`cC*4POH=313SkL@}60kBJD8 zsL!anrx{$`SIN)(`a*$gvEZVMLOZ8jRE{sU!}4dNaP{{aoD?xlr*ucxsJ#J|n%8Dlc zmOq-M9SKX!J$Vu-_4N4y-1KIsp&o2mJkRkB5uP2P~k7v6jIqiTY4mTCHf6tpr$5td!GC70Es-XK8uNp@# zF4cV_Q<#D;5(BW#fImlgmFJMifG%1v5xSyPF2-g#`lpf4UXw9gIoU(^aN3hALTIa@ z<%wQytt~-D%cR>*Els$0^PN|a2dC&^uXCo7r@ZA1Jqn_6$`KCs%>Sm{8f@OGg}qM& zDAceoq7qy13> z_uKpT^--ll#re&BjP5-B{-YpcUHeAAtm)(0)g=RX<8E)RbU2^NC|TkSj#$(JbklON zk-{I*1)UxJ>CfH2Z5}!2ijHYME_sagg!8V9PIO!hM47?rYotB$YQq}h>;UU&h%LoGfB9~ z?tZ#L0S=R1&rq~Uu*d;fl)1;#CM4xTN8`5bqtkT)DR%d_ej>?5UbDVif5CCkP!_i7 zs@*Es|ITA`uElv*NA~(&AR`VAe%7nW+}L~c0blFL=*qQMzT;9qg%+WUe|(PTZO&3+Vkr4bBO!#s1z|7S)N)k!upPgVyv08a#t@F}M_s-R;*xBqU$uGxqnr9$^Ux>(TB>rgC73_>TW2YN*lnl-H`ilXT`)0-myFokB$ZI)Ia! z?0E{InWi=V-RCch$v&)!r$~0KbxZ8(Y_^$uc{|~gw-1{PXna$a2+J{k5i^-~(C9L= z`5Rq=E|y5eI4Ty~ujk7~bo2dHnzSlI2gL-j-t{g@pR=Lg3+m-X0*8-mUPQwy@OXx_ z&lQqfuDvk>I=zkOPA4<)7-S{y%!lg7C?kel*a802)!lIabw&Q}dRrY9Sa=j3F(Nae zP2>5|XYm$0`6@@zKW+&kXe^se#@;a5WNfIyJKQ(=niqid?jtsFf;g6M{;1g-rg+dy zK$GxJ6XYBsW_pP6hV&2}%p!aPV)r6toV{LG9u;lcJAZ` zGh&Fn`H87JX@BPz%+A0vLmVXVWJ%yy0%#U8WFWgrmXUyv5Jopaz*l%k!avu_-7VFM zAAGNFA17SU8jZiO!~o%&N02cT2F7PjQBlR5(HF8ZwVLaPN$BLSRU6;6znpX@lOUHD zF?k$Ahh&agcWQaFg8TOFHu!a{(Zoz@IC;Du@7)8O%*50bWRGOJo+rHiSl>1< zv%+eEuWiI1RmpIXM(o54n0zxHU$dKGGgQtKlsT@PF|{EUz7sW+AsV^Lzq`*VNQ2l5X4{Jza=Gxg>qLop%lH;K_C^4Fz z4!(GdM#7r0J|Q@$mXc)`*hlegS+Ft`)jw1Dr1J;gJ?#84)YR78{(}1$v7-dOLk*?6 zmbpJQ?ncbf^Ai8Ae8!lwxp<T>h1>-Y0s=~#0Y#qk)`_S_&SgS0BM^vZxtlQZt=GJ`F1Y{pj?a`wKu z?4>)?fq*vQu__^QsgV6fv!PJ(w6{SrqiFh${&OL5S7_=)z51S6?qhPh=YLjV1_jtC zkxgf1_-1z)!7&4O6LB7rOyjocplnEJp2qU>$CoGugY6M%Zbo8Uv1E@r=^z5jT%(e{ zQCXTiWAe7yJMnHGHA};HWId{cJt%t?)7~d8Dlp=k)=7--9AEgvf1z9_qRf32MS!o# zs_&Efly@*8e-Vv{Ma#DCzv4Wzdi@=jKnGb|e_np#yU8YU^s-(bPW}3lFq6gV4E1Eh ze$fSFF8W{3-A6qYY>22tuPBu^e2Vt(cWT$J-*CO|SlpGva4V++p-qP`S%r5&fOSAe z)%V~5GO6s^Pvv2;n|E!!WOuYRgX4C*z8|$bmMv0w5@mFc)UzU+nz0@qSh0M>L!dq7 z$?>P+^zj{uX9m&lYu`xtX2DN_&6u^kWWdt+fP4(&yUW z)<)3E=%c2(dW7=ZDj>|GO2#v~m^h?_g5U6Dsdt0#e z9Ksq4u+L5;bw-l3`cF(vw})20q1te6M zHNT3RE&jpsZZqEg4t>679G6LulDWc0UG##RC|9hZmsk3DfdWLQ;w9`Y2`Wh8(@t76 z#TZ+-F)KIKH!F7MiATSnrT%d@jw&-oIjV(Ke3RGihu8JVlq;|U=zf%5(lE#myx=iM zBW@)hzK9CJjO)c6^YCs_?7xcM`pfev9AjABC_U?OU@BR~E-J#Z7jN-6F8|H9sNuXK zKH5kMJ0h|=+=$KOI@7Q6-I){H$-na6FJN&U4w(NRfQPA{Uf>tdPYc=!{u>xb~4Rr>pmpQmlfD zMYXqVfkYwwsF8y>Y9Q3n7;l0}*iD*ag#FO-L)s8}RQ9UwyCMr+FZ!>QILa8|*j!Lp z)wJ-wy)3S&=8hc9_oy8|AFLl;+_q@2+{`%$Uh^#dt9dzE>Z5evhgXRO#2|DN!9}Bl zz^V}nIHm0aDa*m;1M+Z3W-&`9g>*l1+CtLh^OL*u`TA{=F0qG)!W2}w=9VY-O6Cdv zrZ|D-SOPXOxn2@P(~(%#i0XG4w#;by*T=`R%|4n5Js^~ssWE>HTVstS{-U73V4X-t zvB`^@`i9WuZwzX!l*yO!f_$Tn15`_(!YAIe*Q;B$J?+Hp8`d_cHP)BQ5#Y3} zR@8}O+;xqcs2gsqHf`|OvU_mJV(#d=>X2HgnkeO*_=faFv16}%K&C(cS3U!sA9y(E z!&I643Q%n{C2ui`ydP zG^zJ3!qQm>Gr~<$*5gU!hjV@=(q#-U&Gw3xDvt_Zf0h#=;V_2&>@BIR}Gk#hnmGR>wben8E zZ#((ub7O#PB%x0B(trg`(>eoKfv7=^4M(}al^tmtqqYKNm6m^XK{aA&TF9wl^mf03 zlqrNgBEuh-iH$zp-(42l0nBPkE{-#%T;Hkfv>`l&bBxmY)1T;h8~_65UN0 zHmSa~oldwN5DR9Z_@H%zs-!z!Ppq@=N)AOx%b=86y}3Ftb#REIL<8_z-?IMCX9&>f zh>4Lb9-P@J)^2o3yU;xLf4t;wt?8x5L(`^6d1c#oK;LXk(J9aU{CQ8MbENI^ibSrz zgJ89!7G7-^I|~a3L~~A06Cr?MlxP`A*j+1uI))pR;q*kQ{2BcAsD*-*kByBwTkB|+ zIlLcXyZOGgz$~gnz32!TkltHO_#P(}r~z7l`EPty11msn0rD^k0fI|&g@!+DN&j#8 z3@Gv_-H(;~uWPMSAe&PmLu3#%1sC6>L^^@ct+RGsFPG47^ujLD56xEF2CW6u2q%HC z0X_mJ88zAECN>~=5YvxlDP(?wo)xiOf0?j&5IQ+0HGXZffQNKl7#QEWyELc)UZtMn zV+ZZiklxBheknCp&RS{)W1f4i#Lf?%`btdy@_&Pg<}7-8F6H7_EAMF%`j!a_bJk&f z*qv{z9{5XXXKTYl0@Vw-abT_m?-l$**00Zg6;yr*uPLF<3nxsbsKtM+PRhp4Y_dVv z=<=5zx+3YvGYpHP>R|FQOy$=U~Yu|PIAnSfK|tkI`jcU0d>6|x|= zZB|!ln%0idrd2WGALXhj5cL~0we$wvKco2Yi8yE9L%Eh<=|YfANGD18^`M1z^Z4Xq zQrNP_f6XWk=BYF`P=*piGmiBAKN@O_gGNp+L{x`HJsYlPDnqmqL}Lw7>h4x2ChGn=d^ zM{lIEpR%N7ZWr#H&;c_^y1526Sr;d(|2L@AtyC*Manv)umkvyoPz-(^6qFqt9Ne~o zWp+pTJGE#&_^Cj=R>e&Gh?H#y>tmMB@GPhm_aLgJ z5P3qd{q{{1s{^$kHupWY4VF~h2&LX=MZNB6$X&C;% zcFSMuOBNS;Um;CkVDY&-G0}o}^Mr}h`)Idf`5dLl_GjN^!yI0L%o+gf=;2Kva=B+A z--2KC!vTjmm-Abw=B>J#T7$zD?u?aF_!6%h7X_I4t*ls1ncSeG9+cD(t0F7|p&e^a zY+5?N=h@^S(YoG-7PW}>b75cmiZi|hpmDp!2j z=aF;+VwVC#Yve|?9KA!nULcDIpNx`iM0_xyDqH0ir%w~9N&@n@vSR}fOkfLMS^mxm zAY;kC8~Fk=Avs2FfB;jz+RSZGaLg$x;?-w#+_0D&r&F}t;NU+YvewZ!dMvVh88fPy zat?AmdW`yaE$td;D@TY!Mws?b$25=m6Cd|=3m<;Hhe+o(wzB%P+84jQ~X6$-A3YvVQs1#dl?>1uwo9fbHs~?$G z8dlijOB`O3m-FEpt{*o1vS+w#>Fe;a7@(vLyD@g4;VnUUcq1G8yV&{K@eSXPNey|T zB+o=g^krCge_Asx3Qy7-rDnQYFnLQo5p4ux}d`ZsUv# zjNH@;p*PNAX1vLgDu1%Bo;H384mW2NdXS}rTl(OJwI@q!H3^6D+3UP$cOxz2>^$+yRISyD9rH~$_#ICloYaAZSReCc z@kDl2i}>8pYHArIbXLz8f%hLYS(Y)&a3*=LJ`)sQ`Q-!?4 zTgDAqjOfYZ)T7=O&QL5H+z=0$I=xAxBP`Qq8!wz{bX(`@u@ikyCuQt-pFVA06OZ~K zz&hDL62MXjNQ;pX@?2d~aHDM ze~@zm5xQpA__=frlx?KlBzN=&s#Z1v)+#SGV=dXEs*nwSi=^hbpReBqKhEk zaO{2k#dq~K+{8%tr1soVv#}Www+yOPhk6w3i7jC{A1-_b%{@Lj=7-6Hd_8S=J#8!z zd;Xs^G_o*#JH9gs|MBS>@tNQ>?5+^5%@2KPl$R~=&ue-aAH9M%1lPsr0GpW32?<4V zXQ=bbN^lc;wZCfAm;1l8ZV&4JeCPz81?X23 z7~2~nKH4e2B}}Mj{VyRUrq0GA+^X`$TvOseqoO@qeWEIJ7+KX_Sa6{N1zv&ANsWO! zpZQLbET<~S=usMRgtFs0>!4C53k>^DpHXE-?Y+X8LD;WGzg=H5k#+V)!u zc~Ysdci+Jz68N8GtP}z2Fw@aR_>05nAX2U^aRJ$vr8rBdg2!xrTQfd#Dp9tvWZsme z;?uTVW0KC-zLOPAOy_G-V|bWUNYQDeb!u8YtA)NQk3}{M@ESjD`HYh=ozR^~Vv0ie zIGJ$Ta>&&k=gOy39luGs zC3VKZ&Z>?0oKTPa&1KU)F*>WcMdmzGa8kdU^I?3lRM_lgGIxeZ;@Sb%eK~30%=J+> z-U6E?o;AGW5Ki64A|JyT;>e&JBbx`?PK3~x}qp}J9>5O%?2`x4+7&{M;JsyJJZ#fINa13$}z60V0s>X4X_y ziSecIW;+io&;DRZRHP_SEv9C968=JBgDb16TFgNMchvUHlmqzr3AP!+Sj@T1WErz` z>$&$G?2uyjZZsvDl4&2}3qA`XelKetBX5^>L0w@T2E9IEpdWzVX2Nf9i_C?DMhwaCTCfH&QDB4jxH@*Ezx65Da9az_6-wCq$cqp(VZ2^ zS4X|g=>i$g4G9OsYcQGPee9G}zG>+TOwPMMA5Pt@D-dw!T)On5-E)eltriK!GIMJmipyAl(`p6sJ@`tAI|MB93S7X$gLD*ypu;+yU-p)&jvXe03ZL zrEi&_1SFupzkiyTDDyv?H^r*vKX)EPe(JVf>oMSrSOCpDa2+551vA`=)~`zffJ`<+ z=+l=7y_N~5t4$w40#TP#q`sEj!&l?QNudOKU_b;KaIW5F^Q-SYgeeOVB8?zCENZ`l zwyO~aZwQSrh6x2xJYG}N4M2-418eCbF7HiH_Jq}8qcIA2 zpFSv1NL`v;Gq&jL9rH5~{91dLjn(usMPtU>tVi@eBjJN*({1?%2^)~aqLB~)uMY@7 zr|a%ayuG?sh0odB_d>$`6YbKQgl0#|V93%K9h?W}5^ zcbn4U55R_eq~yW;Ew5@8K%5Re*>(LjOHHN@B(v9nI7i$QJEipoL7PKYg3k>4Dk}r@ ziXPsd%Mo#oK0d^f?V*Mt5wK)%+LJc3(aYTfv4>iMdHrlIH#nbX3?3k{LJbVQlnvs* zBXDOZ+qMNh^boWC5R;Vu1LeO)y4YcEVc~C;Ia19lZzh@LCHjaRZ{Q#y+>6kv{4p*D zA!rgk|0ucym0FyZwUECJ`e8ubVYPD%7g!4?$|{@kS}UurEoTMmZK;}}dm!BJJ851T zdU2`cqyJPjqwQ4ql`BSKjGh{?#5VHj_}=)w^v6d0o2pHRd(|*U8~GY-5xR1^8;RhG zV`hkcGXkl=@ySVmF)z)BGtUgbRp}6~M?5nFnO>51Fjl5a@JBqE<+9(6VZkFiL2UQr zs2;xhIrt@nEito@R)RjE7V}WDISQF@0l(Gg%A{{qY{a$n#jCoUb}?Rt zsqH?-Z>?VssHCBqv;Ujg7r-p9xrYMw?$^CpZ&{+8c3r$!)RrJxt~V%8U~2T9nVxLM z%ioFk4E$cbrY8Nr^QfJe`^jesrpL^hgef)%Jy8a5=MrjWIe1r(_OI>`mZNJ+IRxxh z5#W_#MvZO#WJmT*K7ks#hu{9HqmiOhT_WNFcL4NQfch*(D)GRKth#@XR*Hlg8|Djt z5G>3Cw+sD+l{XABDN=d4FyO(k00z=E7%yFXsbd*d=Vhx`n%H0@H7f;naTEBKtT1~N z>`F-Y)D7`L$KLdoc)=vn_FE?YO$Jh~cH#}|6@w9`c81Q2|0FqDtE$F~Gl|IBl|wx= zwzYIMO}yR@IRskI;w3%?@u17egt{xlb-6NN zM(?NZ>o&L1xD5tZ8z#`!P$?&q*V}b5yle9y{&hA3uMXmQf$_<K^hyw%X zI|DJ2kKfv?T->?#B>o$~qGnf1AM!h!Fx;C+wvX6~WN`INAa_23IOj!$=E)z=dm1&9 zuN9b02r1WtYX`j0upF~3*}mk3RM5_x>g~|=zdFnB^qC);PL9#UPE@pX>^UlDQL(9s zR(`{@@y&!wGKj!C^6SxkMG>=T`LJ{Q2XA5-$YgPH^~|3x1=QdDON@JAw(O#Tg8g4r z4tKScOsjrsi;nsSi_X>GjNxK2wi10dGV`Zn1hwawQ;wn&@9Q(vW#!+0O=$nO^li|H z%exrH1TXMX?}!D9cm>Y=6_xgJsJ=g2XN_>(fQtZF51p-j5Z!}o2Ev^>5iM_}YBYdS zXgPb47a^as zz^ep=HOQxIExp*ILcd4W-_3I-`C}^t!0Hdzl`7d=knJJ?M-qf$VlBaKuCMv?_E9h3d z);4;Faa3R`WZ0&TSLhk$>E7<-lZ&?en_JU^_K#}~`@-*z?YXL3tZhbKbnyzmz=lEk8j`e%D`qp97wk@!0a>y#FrE7}HzWfk&9Xj*y{`KoDf8xr(IM(V$a5S(?( zr@L&m4wB2-?73qYSy1tiUB{vOheTO-{jWavnF>@JiryK|=t%JHSYp6N^C&7S+o#AG z{Y}9fI=0kEe=Ffj?Hti4+h=7nBd4m`)YMd1T>NUBhb!rUR3!O2xQYwv>l2N*wiKMy zWn{WIPj#D^cJsi2>QdBHqB|qT9*yqi@6r%L|+#P(bZ`-*RAB)nd&RA1=KPENC ze|VFI6svhx$B}sdnkYM9_HQ`>9xHN5+T>=-o$=U;$~$e|_R&{Uyg7VjH075slM~2U zlfx7>`HNFm<|R$EYY5kU?BB<6F2jA_WSq0 zaicu)G||#;)YYX}2wthE-tC|a5%1jgZ+1X$f6n&;J474+a72*T@#!fJ8uHLcWVG9)oIq(7kf99>)-g7@-2Fs#GS;UqNOVlVIbD&Xh?k^VT3 z5^sBa$HrQ)Qc+Rm>{i7>6>Fj;s`Q|Vo?)V%ZHk%_6LZ4rF=Dwn{|e3X$n@BAo-HnW z-HpEcQL^~1<|?+KJ~PA}I?qrG6${I3aO)&qRx;?&Td2q?qz#O?3rKr%Et%B2c2r{f z6$wnYDdpAnGi8{6Ica>|)g8C)lIU?KB9$pCv7}5eWG_A3;Y8_6;c-U5H40ofWz%-CoRotqI6 zSUmDM&CMwY=@NKK<`;V09cgq&3$hu|%w6{d|C9NW&&9*>LeBEZ$;m^!upW#*wKOQs z(~PRB=s{hyxahCPjm*B;eXjEe|Hq=+@)_uxD%({_KoZcUvd{4~l!>w|-&6Fj*x-nv zMt{XxM#|*;GC~sD;<{MVs%DYcP!{)G?O~J!=PPw4OWhC&&EGbgTk%Num>+#%kiRhq zTB>CATOaiD%TB2v*B2fM44I(OW%{qtBjUOP9%jqHSwYsHypg}ElS4GUX}*rglcXfG zER|T8iHJfn(*Cp}EiMlqA8uryjNEVTq5B~1J>%B$fByGA(HaL?eJ0FXaVnj; zQ{JSzl5hRYet@+e`#}ICF0`mFCKyMO3zuwwG3odAw!vUBFAon-1DVy3OVK2c8fHz} zU|haA5#2eD;!fk?G;u?yzT(fIJ)gAi9pO)SaXIr^sHz4u6|`FQHSVt83}8QCC?il- zDwYk}pPRN1`EQXa@qw8+u2pNV&H9k)sJP+3;K`89JI{@~kr zpsCA^{To)YO^I;3MmQh5l4cyg@VFWF?H{HbXy^ElYd(AO$K~Jcr@qzO=HX4PQ}#5* zqnp>22P14w$g75v~Y-Z9N|^UuH@~H=~^(K}JT4 zYddC7?B|Q*=;$b(qvX7dIm>eQD*&w1)tmB=r83I%P(le|;fWC1*Xs&=h~#kg2>XYE zZFPCj#=mhhI}*n2N{4^(_vFyb!kLYZ==y>v@#0jKu-6l=?9LWCci*t)|MqrxE;f0r_TEC%zx^tcH-PaH5%KGMd@M36t< z_S@0SaHfjt6`uU|-c?=IB%hA+^_G*S+aN|7Zt|}K=j+gaUhT!>cV+lVsYt@1DMP=n zv{3aAjd5v2P~l;&_j1*}7^YasM;vz3_f*jeVpOO~mGG5{sBj6GbHDh7F7he8-$@W_ zFy=!h$~V4SsMZq|jA7CnsG2{dEjXAH>6xZw(;6Qbh$0ynv_(NgiHD`y?IX=tI-TH= z4lqvRT`;Ra@MM!2Gq`bkm@I^n|8*QoqdO|e7`D<6 zyy>)>H3>&*rQITnF|x~K?2Nvzs&JNW$%v;FSGp8h+^0f-rZu`%e*QX?ngLJV;Z?)# z=16cy+he+rDAwhwT5t!wO1O70H+I#1y`l}YtowG*NZ3F)5@)mRJ zzi`6X*QL5R(!z5p!=@E8e%w-}YVRYx#UD7^Q^Ou=5Xnn#@iba`>F5G+(d?+IUMJKF z?SA>kBX0bpZezSbm`9qHB&RJa{SCuw9i6l}w*w>^sqO<0n=QSP%Bf$!h7S*;CS2cA zxt;p#VKl6b9=WiT5^^;jf6M1sVB-}c)Qy`fl7A$$d`^~B^`QHU0OR4>6y`wc8{0c- zjV0=LW`!5hwqB{Nc-(I+rKlUBHnt7E*~6%V7@8QZA~sKV}osWYk!}P zBwS5fNUCIywR)>*-=sliZcB64qy&GKLCL9wpw8I$F+1U5R}%ThriR?Cp}W#g7mO^_ z>NUu8xI~P{gp4ZLu)N-ApDHx$Ql{G)T{C~zGf}g5<>m%_xt;!>zw22I=%5c_jBK$`!f=cyNisSc0M0zc;pzt81&Ho z{CVBcvuhL#VWSTt#sAfsaGX#22`$oHc>9zKDLHGFPT%jjAbs=*tuI4|otwZvOY~bZ zfL{lkvK* ziQzc{e{>RD$o;vjCqA3>5`h}wHD5Zq(R;UWKCS81yx3D&ZqM<9F~C`@EBSuei#SFq z3Pjo-yX6~2NjlX^-T<#Q+PDO#yYV~=OfeR$OlxfPZrxg4DTdD(M){_KZ#qi_?P+6T zT}Ca=i4+AJva1Z5%bLs1dnr6!JU)|iza8^o6NmHZVoEh*+q-2lNt{a*@m^L^wW+r# z&Qn&+5~ZmTZPmm?vHEx|xxSaiiamYjHxyzjE8`g$5}fXT=kv{`52GguR{%$=e}5jR zo?2$oN#aEz<)uU(w=SI z0FVzboSC&P63J=>h~&`i`w9Qi#TBepK4{Z$(5!f>TR$GE6z29% zc!DC1_CL+vE;0~8*F==k^$>YylIdohAbz70S4s{@DjWjcc7Kzft53>~jN2@#BydzM zVTkXaRNAZzn>=EF{N3a;rAp!V!9n!w0#9SVb#rqwY4DQAt!BZ1HDUqvKi4!{JGDBW zK7DFwYfEQT6*bttn>+YY&{6An0bIgh+#0dSrMP75Gcf*pqe!PdJ?Pu7(NW?*g_XmS zgmugx;x<{+@5tOOHuks{iI@*|+3~#-PRmazqa1&tFvz7`oQmLouYg__Ch8K z#R6gjyyMf;)3`X-LHGJmM|(;W$0d~2 z$tHW+;C4XFkoQ4(8>U)M<-Wf|pZfl_{%@?!g0Z&Op6Bw0$b0&K{!L*5-*dQu&HVM5 zu*^HXXDR1Y@54CaPubbog}GC!elgD@`!l?_UW%4gS0|Wo^d>(ycl$kMzO}XW_OURk zfasKmUl)l&aeyfXNAj1ZNZH;XnK@?E-C+Wx)&0XcKc3Kh($^_=8}<`JKNhLl3>L3f z@MQ){#JD!`q{Qr$HAW51c|HwSE6LWpb&ru!oT#4WheKc&J)y`EqRZ>~!JWK1``;1$ zJs6!v>~PG{erPEQrT7Nv(Z2lk`rmIEpZpb3LavWm9tB|z3=EXj^lC<60D=Xw5JOpiZLfl-Z$Wm)(^Z znA$!_sO%<&Q;4^|o&4?bwoy?^h%RnrJ=HEhE6Yz^-3AAE)d3ixVC3ZxQ>!IR6 z3(gK1V6ihpJEluW+_0V~F+5!EYC8Nz4*iY$npX!KpjWH`8`mE12-JK_W57JPn#kUA$74R##>oNl~M=N|&WKmKH0e3e&JspN3f=KZ>hYp!%&97ZuYj@l( zhehwA<(Z9~9NkdC(0vt1y~M4TL+SnAd-CcZ8v3!R&^Mx zRW$ehAa&J5lzv`#gMbHeDI1$k=c$b3dE+wj(aDjQota-KuSHY_UaA`AW}{D697RT=lrodjTnfRd2v+)XFs4 zK=aI8jEOa-6&oDeYMy~jSby~Ko+1bB{cdDb#?I1zg?^o**1X~Q`Ifd=V!r>b{bhU; zUPu(C79g(aEyeHuFmtH;JtfV|?CdW0O#rRYvbnF`7d+0}foo-Zr%BCkOzN+fk@?*$ zr=Pjb-emO0Jx79vonkGDb}4b9Z&9LX+bE8^G1r5&dPTwb#;E#bbNuL=1y>jBFo~Qe z#q&dN<#^6n`-&_=KP%Aa+jeYW^ws!2l|2j7}>7U9|bRV1|KT8Zc z^Sb?{f&=$f<`5_gj^))!6%)>Lta(}s)+y`LmOOb1b8N$bMlXXrvvOB>_T4V&T}(o# z^i_LT5&pud-qn6FKXs(VocYcJC0tc;hz6~<8hXFmV06&ipAPc0eNyx5rEHFIY*2BG zeQ^hI^F~m(ei}&95vU#iLA73#DPu~$0ja5hSqe$314Z+*-&+y#335!tN;OvYjM-{V zxTXrlWT&!g1SF;bI`CHFOS^n_H4t{PFL)|Kn5^4@Oe_d8O*mdztCe zeWRLOR7cyq?MrN+t z*LVCN5sWd;2jt|AL1jmxUryD1zgnfoyfAy5IrRMH%YN`nafdK2v_=>bHRym!zdu{= z9vm>(p1;%3ucvzO5fz8BCLEL3G_WxVl;mvBj=Dp0yENkNuefI*^OL`h-I~Fe0&)tu(m-dQC<8z_J}!-i-j~ zsY0WKMX3DnJm@~DJKqH3f8{Pa-ueo6rDnz~fJXi}M93ggT%p+g2Jb5NKS<)uNfT_Tg_S9U??FX%x8}rltMQIOd zS5%?To28m$+rNp{U;+FRDqrp(di_IN!Dg>VT`xVOH^zc39 zWEqS=e>^A-u z1)n+5-KmG_zw4dLisRW*+3RharDbx=>UEeB=X)^exN+lSW#t_<<3mxnoL!jjFuMy! z`$-1$H?6QlrXrFkrHrNV$8uFU7$*X>Qq8n)(Q(NU`w9JY3^v5yYVbL$O8Dh_&0e*O zWE@!`mgz@bn;5Nq(4rjp{&*I|8E8vZu()i6a|U|rm%cx5__ltFBp>071WW`#lUdyi zE0xu#x5m(}Y7*-sfA!qZt)pZ&hgjUyfd(I5WocM{Sz1~yLAHhg%ol)UHSk)(V+9#| zp%^rI zBZ);V$Du_a#;K&ve~re1MWu3o-oGN^#%J<>H5;BOc02NpLf0NUYmmDH09v2>m7gx}?;RVs$xI;lj`b+zk3sPQ( z9$^H>AN&MS$YPDJUc4~40{Gl;?sVtguEkfY0VVm+0Ye_unJcXmr$edJOOK~s_i~j9 zY0V?AKSgzMtTSJPqPUGM{J`DuHDmhIxMx&s>;nXiHC+~#zp_&Ei(fhZ5;t&e-D+6v zbPsS6&n`j=s12SF`-@0@HVmR7V;B-dMQVlT9i5Pqaq+m{q!GUHAT@)x`!9vO_kYaV zSaq$vDlSY5_c1#@#5?t`w=#WbQFidpw-ixQed_i5uX2%7J6l9mW@%YV$D-uemmM-P zGCe?{Tz$Tgur$$obUeD>a1-?)*Mc)_;h>T#MD}dxMn>JE zc=_Um1WazQTtJJ1VN3;sEpZ+S_sqn@pk`MmUGufR1Q12UK^g}bE&;P`ZSdv6>hBr5 zf}EV|W1O%D0QD<=hrQ_A1@BW`nk9R&^z`E4pE^<-D_80mvKPaV)zYS}5YwI;=zu`dyB-z$>5Zj?z+FCu;!M9r1dOX^w zq6gYf2&ORy##)JHRWKM4090f7=1sLuX`YFAIN@{h(9Mt-X)Gk6NqDS^DE9AD!~;1g z{F~?5Qo zYx%q5n^#m6BS|abiw=Hle)pQ#O6*(eF)mJkldEeEim@1;ZFp|b-v06haE=jpL16}3 zc4NU^s%H>q(m|%Z_^m)0L!9zKOw!WxycPDfPN#U`_}h1NX&C~;2CZ_or0b%Kub0g0*)v(scw2Mp>>9_XH ze{)y6O=3UOaCjrTdzUIuF`#Yn3Y;n5jByIyGylix|5$FUthl`VU&7GF&SeBk1Bc`4 zo19V{adn3QZu|fts#dV)n&o!w&go=m1Z!V>?Vh=r85!0j^b7f#rVZ+*rM2~AvPhah zG^dtHd8-`ZsC3n1!ht>%ru~U92#0pxv-$Da5B?*I9uHR4P$Cl>D7-~wWNxM8zg_MO zb(rlz1~2RF9T1T8D>9Pwnr`%@Vp3C=tv_J?5~Ep@F2WYZD5pB}zzw{(GBO^5Osgvp z#`0OIqCc}bMUDpnpGB&LGAvUfW|kUU7rbAPbK88XuYW*|1(xzUUu`r~Ik~v%pJZw3 z$BK7^DDx|v=6-vb<=5dl{nW0?zu(f zMX%j7yEiIf|vtN{r0Zh|{W# zBWz_y?4vH46vo2vkefl6-`B8H)fk*uj;H+XQX^Hcg8V}b4Q_qI_6~R=fAaCQ|Joff zvG{(scJ71!5CQcRCRKc;17s+x3f_E6=dHX^9P?)hqz~19TD#!m6H(LVtJ)7BDC{>= zkZOs(&4=`A_ftX*uTwMqnk*sc^DGZ=)D7#(Cf`%d;0{EHU|sqAdj-o3Q--xO^WxnD z0v?BVG5MBnl>3H$WHZH&kq}KK=S#6BRk=n?g{3hayygOfx!v88)Z%q-xiL<-f3mXj zqhn*D{0|H2>yzQMf`JSmdd>_{T}Ge)hRRxAcgBMCA#LLP_ivZ%kwWrEko4HQaZKF3 zGk&KCB@Jf~4vFn8ca{%txqJj~amYOM&{9(66k|(%9-1iq(NSf!Lk@j>bbaRL=3u=$ zqR{Ha3N0NS zu2-6HB+7FT-X@9;9@&k(`Y&R2eTQ>81^Hs*yAiPcB&M}0m8BdmZ9-+`34RvU+)z$# zb9@&=KqMyVm14m6gr4{|*>))}Rb1S!yE_yDrO(+}ep=#58dk~UjcajR-o>*M`{9$a zXGHTMKUa~Hx!4cVo%>0U63=*32P`AEIxQ^=Tp_<|mRs~M8t%RLFkl8nvSZ^I-V888J@XQX zmJg{Um?iOHkLKEI03tBa-w!NT6&vDGsNR9Xw|tzA_FQS4m2 z;PgP%WmI9bvHMx4w6s*MXYbb+O5L|>1PjnLeg7U&+|_4R1vByKACHBci9>0I-Zckw z;eEMZ7eLIU2D_5EW3!a}RNuAuOXy$$LKMXn9?FwRtNS5pXhsr5lblVZ&%qE+d!8-N zP=g?Rvv~5AaN_>Z;T5^`>?kqSgF95;^|Bkj1^N;;3=2tv*`#KpOR2WMW}&fN*3M#$ zQGef&w!3U79-FF<9Q)lLpQ%2?BJsgrJ_qN=vm5%Voko%e3m$sNLq6khX{IM#ae4V} zv`_C;`G2_#OA{Moqa;`hT_G6f)q1$_*fRN9uqZ}$3>#{__GJU}FG73`a(XcX^ZR&{ zfqMT@?WcPlEw%-e=r$$-vfn5m4VDrpgR1)+oX*@lgBqN)iPU)^)Q+;;ZN|Qf7|G+! z!TFq0Lu-;lYxD@|*B!#Kq4XHO*Tj$?KB|Sv;Mz8hD9~$=a0a}dWQmN)F-(zv(Db&4 ziVPunUn~?a{8|CC)z%lprB7Q=UFX3)Qob~P{pH;!_mISAUMTIC&Q~=k>BswAsuaI_ zo_`JcEMxJFfA~Q6hSl1+j33jI-0+xEDao$hO#QlF*@7&H4=1K1#nd=H1Nkb zd7ZZrBNk5cJG^hnV5qZYey39AIJyi`Up%03Lz^lC2@i%?N>&x3J0V*K2OHo9bo~8n z{YEq^{s%9CM{#j#^Gmzm@pFuG0OegT#aMOZ^>3pR$h=D(xYN(c!69O2_pF`R)5nJG zOKhGJ;^>^B^v#}*Z^!M|vA1RKo^r79hL?=0^GtRfoT|V=LRXg(DjzK3fP1^^Vu#E` zbI?J)6B!xF|MzUg>uN{ewGr2K_lK~#`BV5@#%5;u>nFbi;BN@{o9W5+xb4g8N%cO$ zA)EkV_#zlXfXf>+g8*l~{z&(C8UI`)L*!-{pRBndf3dw4n+)5F&QtEe!`6J<@K~Sd zJG3ILJTf0izFo?dxlJ>+;X&VQSUWG{>R0H}N5a+rCPO14?B{6T4swZH)RaM9x`U-_ z!1#UBq_^LL!t8!Ix7QsG0@|yqR=s343D=EtyYCnXq?)pHqKtOlpe~aGl_z9)r>sSA zYu8$A9xMLEcMF^l(Kx&pw!*I=oK7TmE%A)U{KLIJ zu;7YNzYG|xpLcOD$u<#Brgqp8v3HgXre;Wtz-ys3?^sV4Z8|O|PB+Gw0vOM>`9$sO z#oR%q*SP~Ee7Heki4O1Ulj#D~wlWggX!DL%Fo69ZK0t)=39w~t8R0CwTEP;Jifk_1 zA$I2&^qtS#Y1seUr1R+CoJnNUJ#>^xQh$ZViIr{R9yd59@J-Lmu*=0kR}WSnz!1Qf zlY9OmuDzh>SPwQPiu4E#U;wol5Xg<;28n=_0UZzLa~Q7w85Y71-4-zb^ajNum_wn@ z0cg*G#1ET{+TV5_R&%#1$f~c!E*zLco)H9c-@^|EOxD(57bchUraX5C>F1zh*`04r zg~Y11+x^XCdxHssZ=COZR5xI{mYL7aIjmr8d~cwX<>Oa^m3whzgjucPtFoQrd+4!Ajkb?Qb4!M&rg|YLXlrxR0H%l%?b;~o^5#V7 zL11dDr4k|%Svz>2?G7(VLRQB`~xuQG2?Z(947 zRGW>`PxBe#uWyatBTI!ZQ;=arJf}308iEmuYHVB4jVZ~JwEkr~-2J2_pZ+dn3Zo(v z?VZG``?SZa-s_FB!SuMY>iszzJJUVStud#wL+GTY9F~5udiLdH z|7${$&%Y|)vA(M*qeBJHRnYNMq$$@>63nZ4k$0v(T(qraOAJdik1_1QTcEjt<=&j% zr1f~5yDPHG$ZJP?VHse3aV3PF=N^}y$5x*E(r|X)s?69IXOZ_N6&haW&q$@o;w8*->o zVq=`jMe)VFvG1Od=CTkOv^2{U;%LZc{20xX(X6p~0PO|Z{uj1@zO*rtKi8i5Cd;LA zXIYW~Zcb)@Zkj~K5d>+s3QHUmC>b- zAmB-7S3dni>pg@SK7TCH$$`ekD@}u0cfViLtEiH9qj$n?5o`@QHs8`|NK35YK00r* zW~U0Iijl0-6ZC0$)Up69tGCew1qC4x_UJ0{f|pkc+TFW?mu%7eN4RMBN%%8Bss?xy zu>D;6Edg-=mhHq40YS8IEf}a*?<(PO zj*JP4`%Wyz$T9v~|Bb877x0>2{G+m3rmOW@)Ryt8w~SOM6<(|Xn6J(gOx=HA@L=FH?1&M>2Y= zj2}+F%iT57Vc}*B|Ef!%VS3Hd^HJl!Zk0;*SO55)ysX__=as+3hP1_RYAtMMS1&U8 zR?-o7jH^|FHO`pdzV0b5U=Ow!MDud;yO;EjjAgjavV#Aavq^#>-jPXj^? zwX`V4t!InkS%}h__&V5n*2BK%av<=YhzLJA>7{Q|{EVNA{Z7-cSCMmZqEw(gtB>OO z+&kqW9p%(CcDJ4P!kjud;`4-WRViQaPSoJN_tJe;}Qry5SKUXJU2(J_FS@> z6w@+=K0hk>Ne@DK`ED>S7ACX>z)`idu>lBhFymGK->ZwQy}i7$vO#RmM+j2g>J~+0 zdMActmvW2_>(J<+e5|uGOmNVTIM+}cvXRmf;KI)RefJ979{?KM_v<&%);(}ORT;$? z6VT+cMYJ#tJ^zQ3uowZm`<3VKpOCxv6XLrL;TPJRWHPy_qGAMF9}Gr4#1b`bt4%bE zL+`Y2grt0|EZ1^zzfB|7QKDZxo|1e&wX^16hidiT=BlY?x#U4lvb4Igo-1z08If6du zW4?*Or$=%s8_mCAn^slD;85RGe2y2wyigEUQWX@XKRCIqnshy{5Q}DCXN~JVfhx~q zrm`)AJ2bY@>0Fbo^#X^U9x`m~W>OnLiOUktQdd;v?@GS4B<}{kigiWFskK z&qs}sz3WF?Ty4%% zrk>~fajT*Jjw`DkcH1F1Q8IDlpN_( z+S~ug(4yMt<80RXe7WrQlP534SDvJ|9s|lHI>idC>`hj_MFO@A)CoA`0zQ5WstDS> zuA6G6^EvFNOqfRg>u!P1@8NknK55^++^>dpIaGnVy_%V`_WNIjjE!@O#ok`ZK$@2J zghT7}*%_8VrZ|}OK_`ut#(N3$Z*FRc6{MZcYVB9iiEI}J+wOU!@2AE_JtH+5Mmw9SsFn?7!0~6=yN}~n(%1jI!>`FL7QF1<8|Vcg@G@-$qJ=xQrV~Q>gw=0D&NpQ+012XBmLTy1xu(D4B^S1~*2sllAQ# zqMsMKi?RKta1dDZ!MVZhZ0Q;7l}mxB+~CPN)!LEAuBg)-^JS)&$(X8;13!MALmR1{ zQrombMbjmEy*}y((soWcv2hjBc#jyFV~A}h^&AEbBXnNH7>mDua>m+7EqR|d`C*TG z^0pDnM93XVqw}LR^x~nWh8skCqOjBI(l{m)Rl6=)?w&i&Ze}OH=gQ?2;KbK$!xwJ& zv6Du4dz;2WKws`V_2=0l;x4S4#tc7dq_V0tomaF7)KsjpG}JzA;L$xD()N)+?N#n^ z>3qDgd`S8Z56Dt8j+SaKZn{w=yx`~@A<@hbJKjKTm!~_TP$=vFQv27={!F$Eg3E{k z55+owD3>St|F~de1sd9*>6LZGd3OG_y9{{(Q~2Va zXuJrk3b9)lk3EIrPePF_!}EeS0@a(gZ`WLY(R^$!;XCuD_AR)pjX?Jb$JNDULKj~) ziz?_-J!k*+uGF-H!qW3UG1-JtA0%5pv6LKb-%J;3Eio7>=^bzwor45ID1zV+1+{$k zc==kV4lD4sva+aQ8TS5lJLiiRRWKfK+x!sXNTwylf4e`+tB%-w)tzrhB}X~VshDfI z^>kN7FBWeqcF>7Y%vkh#Lz(0H_Xpr|da$23wuMN2VYi-QUG{d%tCbjWKfEjKrop_4 z3-OxD3dcpqgL1`2Y<>k6&?o;2= zi6RxO?`uyaaIgP9MPte-+DAlpUJOj_maA4Jlw*qF~z1*+RIc@$}O^yaurJ1?$tcTN$30iey5Z< zSDVpM)SkHDUTNj6zT)3Cq^wG7k5oy>JWCN2A86w%S$nh{T-I*@U;sQ?G$a7)BY2I` ziBBBKB?jTBtLP@?{0;-Hg#fdc7Uqrs54%?e(FkXX>*~fU(ko6?sGs-FMsQea;b2T* z&Nd()Qz-Kf5tBC1>cd5m8#8gxIvTtgASqdKy(p+3_ohOcEXyN06%QJdLd1sWOVT`s zS8LL#EQ~3Lusl3%;)8R0ZtiMEGUy`FCDqP*N88ESnVp~iJFtVhA>(;jt6YbnY!mM| zfi5Lb!vC)f>lJfZ85`kMk(H%jn;J-|TY2qbLCjYL_0z!@V-aCC&TT@2K-A zp35CqTBfKd_dTEvqzS~u+gTFZRF-B)3pyL~;^|K6HPL8vVS!<>n-k4V*IB^J6cif$ zK9bPf8oSGc^~+dt#NfvJ#M9D9CEP!kO^y{p^z^gXQWfLru&Myh93Y#CF_Yvd(yQ)n zsv@0}BW$>3;H-hn7e-WY;sNgpTV4jDPkF9KsAQAfGZzA&q zxJ{P=k6?lVG&!!{EJo{{taQPb!u0Z4@2BAX$^zYs2yPp|ijdufhVROKPKrx(>d|)b z8)5GZsh{pm4-qG1yv*jW@j@ji)i|t4LuaL{wh2*+;F#_RgITO3tCJbxvsA`_0i`z~9N!6K5AL|kc=Q{;?Enmz1xrA+W@`^Pr& z4H+G>7sKON*uIz@@r7X`-rlbc-O|vzAY3fQZ@pfGzQm$PXPvy*K>)|#dF(Zrs#r0D zC+%ICw)}Va4qpBVx{n*u;pF6`%G?R>VnYKhj6S(zRVM4}8dWZor}LiAV076xGl0-n z5C@_;TJ#jHYfh+>$HbvO+qpPj$4A~S&Qa1)kzu?_Y?^b+XJENY^-^d2JpK4ZehD)Z ziukKcws@8B16l^+c}dggM^7)u-_ju3XMW2kSoC_pbp=8c{D{!a8)&$c=@IB0cYrVU z#mhZLPW>@9Ja06S2h%1E#0?_Y3JeVGc;6f7x>kjmYYXlqDYiO5Mh}~{MN4c7Cgu2dYNiP2sAonfk zTG%+fIDm+q^3;6y^XC@FhXFbE&_vxuBH#S^ToNN1t$x9)stexmogR`51*a${-A$ZAns!Wd<|4z^sYHRDj< zJNAe>A-bh<{107ylLpr;Q~A2N)?WsOdlI%sBPz%Wke^U=EN>%K?)kSlg?^%AobN7D zmtg>PNf$q1-itSL3@X5isQ~{E*B1}NyJoR{OiXf_)m$*ibq|Q|Wt|iH5oon;$7(lQ z5d%F9@*6b}&)JelHc{;@%?w?WwYD7#^=;`CvAwh~de1tI$<4aVya7&?Hp6jn8?4AS zu*dXnzJB&&jjk_)X>IGjZ%zV&9RUGnZ&(x+6z;abWWxhot6q~>xX|od<{S^co)6eL z3~)`N9T*q>?kyZuWnKZ+dNWAmpkMxvmjIORdLTIh{J#X+f6y14dbh<~FI!(&tt4o(MxyAaSGPF6X_D<>2Rb6X%UR9j!oS=C4@_n8hY4Bzx1yUL(nho;_^s99hDB zp=JoIp@lr6kQ*!t4>I#<#NK^*PellAEE#!ePZ&@JvUbw=ox_A$yG7WaSDRT;Q)NB_ zp5D~gD>`7#p~>7Jt3fYjfWHFg7A_m0G#T#e4`53J+z%RHt@!^`q<_tk3~{T*r1`WY z;ctO?1yuqZd6)8%^p*wxcK-wa0tuVa*n6L?oG*DB|7}<5oA$fA$0QIrB$teH`i16O zS%iHom_p%FoqT+HQ`i6KmkzI0F?}>~#MZ9OJA^m=Ix@<4 z5^JBb!LeplUHAI|qc_-^z|;ZjBS=B~2AnrzW8*-PEWDRD?ascalPq0(I>yN^8z);M zM8BCs{oo0~&u0YBRI0}l*EmR9-J~m>b3`Ok?~eV9_j`iCtIPZB)wZq7wDk!!S|eCk z>g%|Gvg+wW-I1^iSya2QY4_=!cM*tth^+0sF${qGcf6I)0i=+1`p8!*-y^Wu~IG^uW^?)etv#y96%X0YL} zpc5er;9pe{rlr~Rk@=Q*a$~t?h#l+sO0^ha_dnZSl7aw3wJY6B#}!Pn%{o?zZ|e603xX8|C(SZsa(3> ztzUuvE&MB*)dC+CEja^xU}5sOr&w@%f8V9U>=`82pp6*8+C^8N$?m2&)y-fL03AlA zr>!gpa!tOOgIDQE2NexHrdbuv!3nYZj!{fe3GF8a3sjh)w38RYG;NRh?&CtQ9`|Jdt${UFJed2%3l)s z8wrHR$5!vW7_PP=9+8ZnntJepsDt+$Rq%H?-uh=#+BV^J&*wd9``lgQc)V+ml&kedHh1orkac%`Ue;0HZ5LK{5*b7i7je<=2e46p^>b=6EW zi&uBFTz^mTw&Ff#a=tLXS@lLz(Ax1aqWA=k z{#PeEZodH1uN#ySHz0F@f2U)rP?KZIeOeY(`9?fQ>XCGYJG2g0gY&}`{<4?sA_yw3 zBw7|)4m&EvZ-tf@PtibUXUdU$U|KchYn-y)*!n%>Y}ay(GkUw>uPDQsshE=O2zt7=_F!|{aMx^-s$~tD24#TtmGJM14JsB1v?rJX9{Z!dkixn{CAkOR@n z$1vnt)2P!U>R@Ww+})+kkQ@~h=<>)*6>Q<^iCQB&{E%+IQV{xpZtU+91o3UdDrB%> zo%qK)?_iwYU1;&mNb0^A|G_l6@XCkQG%|>JhmCRi1It)9ELgJAXq-+0d}whmu}17lkz>pc~Ij()9xm?H9)(*0v4&zrXBx(c+FBVroJUKb3U9=s930*LKSbN4RPjrk0V1=;v ziuZeqyeWs=?vxlY%0q_hcbHr;7PM&w! zg{A@GX}0W|BerGl8Ee|b@kS?F=%a39wC9+ol=C^X25dtPWXPPy#nMqdb5#*1lUmtg zTgb!ZrI1Hvd(+iAb#5SGjm)+{?ro|)IEA$*jId+l<6`FK1v71GEUYd<$}FjO3v!f@ z-t;0xxCKc52Of6}9B?1^W41mV;w#a>vR1cJlPHl;_&B89Zr#mX)wr;D#DjI2&A8L$ zR37b!!Km>Gb-a=0*?rnWXr1H~Co|oi9!K-Hi{5?p znv-k|yfOI?JMX3OyT<|`$VQshjiXD<)*!-d%JMGPQmYY#nuI7I{cC^B*)|^gKNeF; z>@=!qL5Ktj;@8{Q2d zuX+{+b!Ocf{P9OruUwLM!X@ggo&6^2T118!Z!X2%zuAlP?UIFfc^l3b#!o1xH*o@B zN8+XDzUQr(VwDxngh|MC<{91vOWs`I@I3Q9@Ao<>)?Z81wq5#0Znp}*(4Zbr8qqnU z@Mv%C?&hj8vcq~>K_R-hwg^Xj5NnH>6doD=v&8@%urUG&(-Hg?e&i>&6&q1CljVRn zDI2MiUvia9W_m_`MN#OEU7g?Uoyo@FPjCZ3iL!iHm)?@k#)e$}FZ3P-8CE8pQc!NL zw*P!=%Ddq4Gp$5Id2Rv)S}0#>f}V*4U5835%-z#gl=I}KP0}G2Dq5$B)8oj;qkY7?o<=%PII7$%s z>?1i60E(|cC$@U58QaU}-}cTN_x(A35P=0ZGH&R;=IlsYc2w7Q*&zc`K4mE3rk<8jt|qoS8rT36v=%ol=!fjAVWyaZa1=2(Ba3^ zf*d*G>=Go(Am+80)R0w>I>4Ikprb&epgmBcLSNGW&~Lx}pOl%o%9)oIw)IN$-MjE% zfgKJM$n553D6hXi$kORvMbvthYLS7c@PqR5@wrWs>pi&cM{$!LV~!7H$F^A=BOp>V z!H=sSD||*(dj%;luOn>q!?eam&*3s{{KUFBWcjcqMUb_*frd9a=nyZHWlp2_nr`{- zgd?}wJfq)r(q>I3AOoXybzT=U3uYkRhd}^+Mt?4cKcmSjA<$8m;Awuu_D9GuN1|@$ z_*@NzYN!Kd#l?f~=kFKk5qRFODDL>4cVONs7|Z>J?If*R1W5%6Fy813Qa6Jagze2)t>y*qe_4avtTih5W>S42g9g{7?9mHRAM zTC-&HGeN#35k3yAP)y9sf?=hH>DL;Pf>oxm5ff{}8c;@#R)V2j_GaBT(m_h`J$*Q? zmlkUBW&v3% z$J|>aY1>a;%(lXLu(Y#t^()OuN`Xt-wok+Fy3Sni%q53}0}B}tOC6JM%KvfTeor8u zloRt~(omq-fgS7Wu;;At@9XSJZyC9A8=Qo=l_|b#?Wv980B-` zuitPRtD&rM;{qC+LX=hYlB;VYz9v1w;d;D!sTTJCy1&`kG;K8(X~DHilyt@C+RJUX zTX`F!HuGLAur#Da+d8I{c`r=Lb&&e;ZaEYnc{jdv|H#ifu*&my#_0H^Vycu-bmdq20%3oLe+lq4m zd@DF~pD!TZW2x&tsMav^Vxz{sFMX?df7GteOv3B=yM$>Nl%epP4iQ^SrmUczAmmLx z5Ma)IIOFVkQ|?O9){p1BlxIsIvOGqW6!(P_kH)Yo@0)Z(7X|O}*k)Z@j3dGAgcm~N z)UB!swAS*svrD!x=@ap#gF`LVg4;Z%Dl4xwGaD)*6M&}=?3jhCeb;)3cqA10x!-tj z^uqV}1+bElxMkMt;?*VhnhvgnF=CrF@5xWr4sFcfpM`ZT?_>(6-@P04n*ZUye^x0q zs~ww>WvygV)PZbrjutL1zo|Re^ezIqgzjZ2ZXT!Pvs~pW=&(GaGarRiE|;zmU};#U z;FBA+7YR%+OLui@WmrA^@H!c9zW01n4exgP8Rz&O3Ci{uL^~8OUGQ5LhE}2l_r=wD zf};mF#+>Jf4PWAf!2Ad8VhV*F+{%?We?@TB@PCa>xUf79O42+j!noTFSc<$LGKA#^FhHGjHvoQzy*iv}G{+vccfb#sVX=0fNomfO z{XE-)?!X+oDP4h?;_4G3o26u z15)(w1mbC25;5nTM{z@bM5fI*?vTJ!UIf44GyS^;VST$K{NgoB%C;O6$esA$Xm^rN#L zCbW%p-vR->!KH?vwD-lwC>QVF-)4E%w!=2b8HWF>?5O^70-@ulrfIZF$R1(?tA^Ls zRno2HpKyED@tr!hZBo-FcqbpT%VCQpAMmjj(nK*lcSyXEVDIcWs3I$>%qctbS4j2q z>+v<)1Fr+O9yuTpfrI~1`hiyn%*T$0%VHTG+YIv_J1mnNxnu~Wom(HxF4=S+SxWzD z>it*DNd(H$fv|h|Nz%ba=cFrm_F(p$U{Mk|UJbq~3)lZfx0A74i}(hPm)`l7Ur#M5 z;B0tkjD107e)Am1l$7_pf~*dB*emE(h2BZ>bdF%8=lzxG6wRtUCtblk%Jp^~p_~(Q zwYcfN)KS3r-{d4aAK$lMzYqcg>J!sH{t<^yv^&8lRrmJ3UXohDEome%P^JEth=-k$ zs;vP#g_L}7<2JC=(9%XXKh@R5pot?R%m1{aL!Oq6eC4l7##Criq4-AeY{W!RDcR(; zrGcAM8c5=(@|;d+2U)w{#+MD!Tzp>a89|l;lnk)P@ukAQu}6@@2&`y&5HYQwVIXtC ziw9^>45s&Iup|Ur-jEarEM%AdD^fvI2;c@m)(zT4rlCyz3%92Xe!e9KH}^NW7jvDH zUw?A}cL9Ch&X?}`Zl-YiC>pG$uQshs0}y@cm7LMl$B3aBo~H6u6-i7@t&!GFKfs=V z+>){U9*>X-v`dMI)-!Xk2^3)sA-R)ND4<|zWf&hQ92LMJrL;C+l0D)b<}vgk*5A9R&zsCg;+;LY$-J1ZC{m(cq$E+j~vJIr#&0D zr&AD|a)zwdvAt3a7fw;>T)iX+&eRxXRen9ZW4{<}tz)Olr3_c8k+F;e)AlA^^YM}x z$4Byz4fEqiPi@N;I*eT$V(3oy=PrL02%18pp~1`@&4S`8ulM_!-?o}tJp$iq+xvSG z48@wFa&I5x8nC&w7?O%Mls)>3f8-^E_9JSLq&*V!{&Bykjf{8M`c=BTAfRGj6?Wc1 z$CAV)r+s1BydV;s7=>ZtsZB0I2r{pu`8)xyDPA@1i;;NVz_ceDGs60-daS|fACyH4 zB{{{iR2l0vZPZ8$SJZUog#q_KuNG^BUrx5|l$2PeQ1bA?fR$I}$N(G*bkYq-R0J|5 zkVshZu*r>$dvqEp!7+E#qC9y*IZ%g1qtj~~zRk2Bf3ICuR(IJ%Fzr#MaK%&A?!0LX zNq8w>M~L6?sj;zfegC)BLlC3FlM9|T?$FhpPfvdR2CmvNAPR>&iuT$>%ki6jjmngr z@x}GpLjqV87;V9yjP^x_C9e@IB5k+!;55Pd(c|GTsPv(E1H{-3EbY%a1TRG=N;E}X zU0?YAJM}$qNq5iuCoDAT^(LBY?DQ@^8mTm@&=9MQhzsC;{@mEPdTQgP+N3l?!^c|z zD<6qC#hl|fbszJSBN8an`nL|pjUkC^6wK9N+dP!QWo=s)PX^W-wju zr(}`fQL?!mA)OcN`Ij=M8$J^3A3>aE4!$|yNB+Y8RC?aDeemZf=bMZWB~$l-Wh*a~ zbe1BmK7Cyt>;gzBDc6AZ2IvK={=@u>QL+868+x|Q&i8NMjs$4zfBtgdkkZxp!<2L2 zAh9s_4f7^*dw$6-Tb$c>idXrlC_O0}Mx8Ijjh9dO`DpFjO7nRH@8MztxTDeRaT~sA z#%O(Xbu~K-MvIFCDfzG?HA-aG6ybkZtEttJmwANW4VW_6jfHlvK&b*pIe8!~!yH(4 z_v7LBudf4X%T*`=hKX2hkw3SO`6OxjS@V-?m zFqd3DElwQlIdQ3M%ZbBLE^cS#50ah9Z`%@aq$q2)QDV7@o?K*)>jjg@^Uj!_E^U2OQrZ_YPs}AmHqQ)c_x}UWzIueclZ?~Mu-wIsyhrlCw zCD<_S3jep)HG3HOZSRD1=>K8!$k}cciKdGHH`*)6d+0217h1AEQxJ%(OsRdSZ+&so8%y@0a_xS_GuA<|iRXD;1nnO9COzD3<;bZU$K6~72P}9p1n-T zub=n>D(|n$Wm{LRMJo(o;^m6w55UU-gfOv&*BTmeqk53%Osv`eY1E zhJ1R$^iiL|Tx-P*F4+;|8_t^^IwzGrg=q47XI#T4bd`u^2o~f8&IkvL2LP30?0ii0AI&%mR zm2V(i2N4qfuM?$FXCN;Cca))a)`1Bv9O^YG%FVGvnf9{_3@!>iLMb>-Q8LZ`$7h)T zw7;JTQw=MzH@}}I6z^sfwz9CKj2TPbTHGr0HmVTMuIAsy@j0w?B%UQ`G}=`!3%z*y{X{lj)n8#x5S=qWtI5KDp5_9lpfqWuy*YxW{sR)|5qi4gaHji__z);w>@rn;=aHJzkLwo zJEuI}$MIt(yd}X(5q5$JN#pUOpfCGFH~%N;!G$KEpK}tfyQZ727%9s7@e$ZiJrb>BmY7cL4Y_MjQ9^hf=55tqaxR*7yl)nQBM#%&D~u)i$;Jq-^KO51q0&` z4I)cZpY3?@CQerfM+la9ai8W{mKD6_o8ad~y$DZVY$z#RT8;esU_RRAbXNJ~720oX zhaXjOP>Xm)TYT^gMESe#1zg(54imFFAQKo?exK9BN#x9h2NP8N*C;3+15aGeXESAM zXJ-b$B+}x++MN*%f?wFy_fgRbENea6L&o8l1=OD+eEhE;@ks?$qd{jSG^1R$Th?{~ zhMBSUsx>>K*bfR&2>XM%i9+D~^-7NCm}%mnN+ahL_ebze{lfdtvo!2xRYe&RHCm=b>(dmaY|Jt*9O zZ2$`kLhV7-v&ztFJW#jrRwT2y)R6vrfsqa=R$>-cl3f2UYfnenM__Je(=YD@pcjda zZ30b*L!~-Qizx+s;=$+-feLc$andE^eib(jrmYy`+=mj9Lan)F=HB!3?{-!NQIcB` z#;XWtMw?%;wY%4W#Zx!Ou3oV(eF8HKzO`Msm-c&2NTi{BF zN_@u!A5okXy}>vEOiaOpj8Bj7lfAOm-?Kc6WVb8-_9B16(NLOr`sTxlN!V(@Ftk6< z-_U`2o+j5&ufoyzX1T~>yXY4|DF8*x97$OMC)bav@DP{ZumrmJ<1Zvt73|9=rM-C91T)_)kBH-CFm44A*1JNbW?m($^R0U<~gzZ4IJ8+R{)eGpMj{$7JRi2H$# zr`8i#kNN>}mSV{$#SW{M;Kq#nU>tl~`B9!dY>Dy@3uhvqZMrbd9iCTRQRX=*tbnXaTF4g4utpv7)qFRDIe1OF7XGHBncOs`&&S(|eTeY;;-KS(UCEv~fMj zw~`Vc3}-!KFf$C@s^fnlsn#QzUs$*RHIm593*!&mJ&><84}x$3V0bd?>pzI6{*F~x zUS9TWdV9{vRl=>D{yyl5LHi6;I?S~wMj=KH)HMbv1%wT8=M#37PS9N zh<{&xGqVJV6Ck|KN3=Wa6f)&$uZBX}$G33*y>mPbDVXt7&w?uVOMt8-jEvw3JlFs3 z{@u)8zk$`8F4#Hv^Yn}?AvcZ4+`Vwsj0%})9PQj^Iy}unhZD2wsV)Eh{p*D-?B_o^ zwPwIoP;_XO!GHQakPyCTQt6g7=;x{Mc0w*0ouU`u8b^Ld7nSoW_inJPG5kn6zu0vr z@DAJEI>W2#ANxv+-kgj*=_h5z9vhxeVOJ@Z4>79KGQ03$;Dhl`#qa_dEe}3TZiya| z++61B0u%#-fNL~IBh9O^F*Qbb3m;_)cgvDnw-(k1fwcS9M-?WJJ5-&X92y2raN@)I zfI%_ONTH$4Ay}y4LB_sqWR4jnut>~$LVW!a_SuSs&HaUUT-(>Ny{H{YgC*(lL>z*^&N)4*X@o=a}uFr z$(CIi^d>nPx#AaI2VIBxAYZ?Ms)ZBG-r|Z5@UwjdUK_BW(9sVQqobW5f@_9tR|!C- zbj94K9%^#VRqt=?Izdwg_uaeCiJE`$%E`+9=p7KG2zmJ_?U_j~e%B)93dawToF_8t zBbgK=I1etqqNcBpmXN;@MnLc>R}Kbaj)o&Hh#F-`P++&j)?I#29x4e9a6r=)Fi2`@ zBHMw>JU+4=AXz2YRP8U?!RZUm1mE59_NNVphKM)SDl`g9V}c-nS44nUffK08;4Ny= zK*3+|Flv*aeLUrOB*h7FM*{-^X-vpD3%C4-l%rWjP@;L`Ut}5i`sZy5Ve#S+bB6#$ zIyB1ihXREKDsF%iKr#Ry1{zdBW^h$U#m9c=9m%3q^`*DnEf)h67~};-o{0^3~M`}H}!NdZw?x`x^$VC~`P)fZxe<1M0#mgEmWjtU9Xw(R~ z750SD zCvcJyc`89&bL9XPLUn(O%r>w44G_tKdcobMScy9uRc^HW5a%5$@jw!$OB? zpRfIPV8Ji8n$2TY9vC1iefGKF27@abj2=KGJl)IoKVSqm6@8rDw)NutCE=A`BTuuz zkt7_8(}meDy!$@&pTWc*cYlieS}EtfzO)~UyP!5Z{`C7>)tM37ok>ul{p}Zx*J0g> z%gtpsd}MU2BX4cg{!{Og4lK*u++)SdTK3~*p*q4!MH*>^yTt1KC1jaw3vS8I!BOuf ze*TmI6coM#=cg6}{HE-24~N`%6raGJiaHlz&Z=OmIM{#WMlFEGl-t#9%hZEIpJZO(&ay`w`G*to^j z+T4*emb+45%7Gn9p??lRSj;KpOn??jZ;?0c>!BjeqO2gKsE` zu>w5j3W$@znu`%T753g;b*m|aw`3&0ti~QTahMt)OrQvM9sBxya|A;3P?&*x5zS+$ zvg0=lU{BqQ2Zk_tq5Bue%75{H&gBvkTK2++WKl@LgA4*xVYaoE~XzRPheo<57E zEw(b?#x16+c&tkX-{ED&uvLsTe1H_-hi-@*BNCbqX_SH?+7x;Y&K6eAc17b>ByHQfc(< z{V9^SggKH)?B6IxsHOPvDQ-|KE-v0z)pXt$K6&)6G+AK&y|hJhuv9uS4_{Y514BIz zAI}&6)04!e&q`lrM;#ivVWEQ;m3LGwxv;&x9h834myGw$q67+tj%Cun(w!a7l3<{DrORwyr>gHyZy!$>sEyT1N)Q$fxdS8@ zusIc@#8aQ8F~NHToE&e`s7+e#^m-JD(?tJHA;YMB03 zuT;~F{Ec{A(dE5n)x9tSFdC>}?{fBH_P5AArUHz&Kqg1rVEnLOBZv;d)>Xqct9kB( zynvw}B2NLz8+zakSF__i1&~(fXjp$39u}h3y7VD=kyMc^W?SMgK9?oTsF0|iq?)BJ z&4v(yfFjj8`b-6O71>5!@*lM9=W}y&17xfG4UO0>TSk>)5R$VFsC> z{~qKH#Aw;rfdhn6#M)~0y@2_xAKQnqeT~V=0onOFTiXi#l3AiD4xfqA3UpZO|6M25 z`_r?3kTA^r??Yah0{Zg}dbY;WcI=Op^8r z@kXUSF&D@_8D=IFdS+){zrIO*!{Un3&mYgN693z4jlHS;8YWk8tJQ{-MN`nEynxz} zK7Z~ea}%Nev>7gdK&PS_?qIy9)rP)6@`s!guT8~!smBt zzyJG+{agimAiFv*(A4Bf2?X;33IM&0pwC$TFEAQ{36PYcsU9pb@KA3;$4%AtDV&_( zDGL`pV4B=(<3~X+Fq+fH$ZaG|9tEDRQ=gne)mh*zB;&yJ^q|fU&Aii-r@9uNL z1`Rh=2McAAteIj$NVg<6_s=d>;cpWV*p8MHKyqci-E!~XU?42*IoThkLE%P!HLSWV z75;S)&42VqyCDsJsGI7Ltd+tS8Tmj ztDa0nrZJhBT^#ePmpS8@Ro5I{yH%xy#M_VAOQefwQwQ%FmbMu>?Bcwo5^4fv* zDe*CNgKKgNOZMOIeMzz-ggLgUx_&RLF5s8E511#@(slsJK4_=FWk{QX*;-5wcLvQb zSPOy4<@Dcu>Msq0_=bni2T_+>G_IMsO+JAgf+1h*uIj>S^u8e?|8Z{TFFI8hwzT5b zQz@&&eYKp@UG94ttp!+%)f306MiQ!|L#!B{ZhM+tD=G;ZqCGDfqDpnI+o@ui(j#4+ z2I~yYq8h9ebB#?enR5T<=XnWtJ}3}=xFth^%!{Uvqeg2-3#D^$a`Ygk1Ec1`fVOdR zT!-eed2ZP?p&~+*WeG0s`(Lpnde{Xh!caH^`e0z8+}70y$X6iZ6~AVV)z2Eq{Aw{p z^;!?pr?X0w!#4B*n4alS3Dtm*oZq<0f;Bfw+6wFeXF~~5tsH(4F#XlcMQ@hPGaowpSdLA4K6sIDDxYy@ ze8%41-Ynqeb)Xdy(T+MP&~+6uZbW?nyAtjaq#KFRHu^7G(cBzYQWX@H@H(RJ5VcJ? zL4Z5>Meg|w6XRgIx?n&J9=(CJe|PX|U1r9gxERemNkzlJY>o6g%;MbeoAFy(TG9{) zqn?`_jWke=0a*!-XoBtS_aF~Vmk!^o!uY<0p$(RJ(654DtjJ-_2(MN6Y#Fn5_e20* zo~^kIp=H5c{i>CdKpZMkW&Ge6V&e{l=MvvGo$^A&4Smyn>pF4nNXE-pIRypo){!pP z<%$JGC0)IMy*Ju$tba1iaq@!T1|P5nfF?zc4lG;?A7noE8a++UO14#Er0nY@eSS-1 zj_a1;69Wg~iWdWQYm~u{&oT7BdMqn_q3lJDn&v<Rn zwTZ*DH05&F; z>3apG>AIGT7T0iL$jr)O(C%7Rpf$RcvQ^_F>ab6O6{vDCZoZd-FCxU%Y5nLzPMY|A zbyW>ALk?ZL+UG=lOYb5dfB4f^EySia9DKBgz^(LfQP{30I={!TKtmr$Zc`Xjd?HUb zjZZG2xtm2RpN8_X%j~x+NHYjZs}Zl6u%jQ;$5)U-VahQc`p4iGJ$ct~)Y$;tCn-<_ zikGE09QLf?l_4cBC5D0no1B?`9Xnc{Fdu zaa0aHh59zIu)!t=+BQ_%7Z@lA%efKk6QOB3_39x+66tpVaJqiuW^4BT_X&~99;st@ zf}|~Geb^aIwNyV#8i&Aq?U2wrlSJ2PXQ$b0$Sj`HiIv~X)}c$2=5tj1=fgjSF>u4f zOaqg`s(CKh2*3u0sKb@FaYasigcAk&Yxf4-NF>=TI%JcsI5%6~OkrBu_#DaC%bQ7G zIYHuP)bV5fYUe>=esEv z>{yUuF@7y|%ELxrD~nz!j*Rt3vqE3YaVWF#!&;1i`qHZ1&D}%xpw-axFPpsOGy5c4 zIF)>GLz$aYxj^H$02)7s<&Oo+YfIH9IX^iAh}>Wl#*BF7D3e_?Txr%+r7CKqj8cz! z)uOdr(jw(?>VjLT{tN6q!1S*JHn4$k{CoFwuI%Y_dUPF@Slfkf{Q~rqDP+2Q*ZZkg z&$g@HSBTX3jKN__3|E=qq799`QeXp$yx6}#uZ3V76rIJfQhy0OnM&{(pCFDC5! z64LtkXes674(c&S5QUl?9G5*M7|~9|b}1zbO7d6-EPlA>^a8N%jm=K<&B7dp)YnKO z0Ir@7kN|SB(r{b>C~jXF;riPjaQVWsGP&RL)Z=eaI}(YYYF;RdzPRr*!G;CRDdJH1 zI_8OSaxd`#)*G15(HYWto9ofBozAGt#zQs~2~&=TJWXVMs_;W#o^8@8$kLO9r#_u0Kwi z`x6ty`VboX=+QF(WPzMR>=kTiAol?~W1xw~XqCnrUyeu3><{!a7jujL?x~J!K?8cL zC?TnW<}9vFH2Ylr-m-g2n^(D# znwu1F9C#{1ia@6&ZcB~JAE2masy%?HiSSr_=l77?F(mq6eDE4Ga_Z|($o(4pN5#%_ z>RCD(U7;D_ug?9XFxvD9cD#c7y`v(~A~#l0q@Jy`0UR2-ysEEImg$7#nS|FixZo2d zcd>K)F4h$Yk17KR2R&7I|KOk$omG|Hu0d_%@cKuQ{a?5*o8Nx?G<^NnZmOD5tz3EV zZzNAo0ST8gNZz3J4Na;X^?S64&_?0h25hmI1(&DAaM7$@R@T&nV-U`RqZzT2+ZfS9 zR`ipFM{GILilL~c`qSez7a)64W)4I!p+94!&YK_TWopZZ&(8nRK?MB$St_!%7UsxzZ&HkP!XgA#34GNKOVW5p=b{l~09@7jlb=wv`PT$@4|sN=km% zf3zwjbU-W3NVh_m?jiTGxn-J3GiNjHPkgOHB&}@|mswzDq7(CJ&%w|pW$~IzcIVH0 zY)PY7MLC;-#nsg|z#xH*f`JxD8iSV>9e+-r9R%#*5jDpDbdqwx6{g zH;U!qbM#MD@fhdnp29Rn@Wy9>Jf|D>xdCY`iXDOoU_Sj%FE0C3LzJ-}*#+!!**kNZ zEz8QE^5>I@CZ3uQX-P|pCbe=ZBKPs>EsHp?zd@c33c*Gm0+<;`Z(feb!=tb53sYg+ zj8TKVV+=Dz`LZRJDdaIXlL>qUh8uPc%7o{4>N{k1alHAoBkYqr5^hF*=%gKwX*w7O zd=jl&9?<-W)YN6YwHvs~!W-D=*+V82mQAG>qA7)Gz7uP^F8iBiNE-$(=t_Ws%OrnX zCsbZExeXb%qX&Ew6&V1E0hK=sn3RPM#*|rT)rAz>jfWwD3;V%8S?i1lI`^9Hj~rsT z$z$8lm+I5=EK~4p{OecNj_##=(g5TM%2r{BN(DxyzFstMS+)OlI|&e0Kj1|JlBdNa znRGK;-m$Ltui-^U>@CHOuP+ok2A<_ocHR=6f1_2i|Lq$S;N>9wgh`$to<2bQhnWie zK-o$kW)mz@%#H&I#(Z~0U@?!7VMutNn5M(3vT95+$EAZ4N@w>>z5ZdX-DopkY3Y&I zclKZ3{%GG>?j}{e{3Ti2DDRy>r}JnWTSP?P9WhTVg?)mTO*GI|jHV30QY(h3**d{=cd%YBOe-1yjxZ!&Sj>(nzw7+eR133Wm<0TsPOuF3!w{; z4kVCu0QP6}$s^ss)lki^u9ds?1S&Jwz7?gV05AQS#{(*C8#!d-S^N4PEAuKY=N8ExX;2S*ey`0~S%&*L*9weX#UKoV zoH$Tt*vo!~X%12rqYxHun5bS+qeFeO_f&vtE!A{`#Ac#9hpqf#dkQagn zgx3Df?WI19y(d5<@e9`?(z)tBZEkTEWww5viv_SZU_6XK_y9oSjxeM7{Y$6b*h)D? z*7J%T<6AyFik*!GZ4di-Xd`3-$b(atfmKgq!t*~_@b5tkBLV*yWXd7M19~xDQXf5o zpROpY{aX+YTiKB@^V1Tuu*UXowRw;X7(Ok*fKP;f%<-ko@AJLG!vNjREM=#d_h%^r z^3(Z_C#kIYnZ6zpCmV!+21gnE-9TB!hI+BL11)I?I)1#ptJU(gm%jU8*=#pY=VT8& zipu4#v`&)MJGkB7d;La=#Dyk6-{3w6I>q0=VSF%UVSC6wlvV>SL8F2ybM7g}YlcJP zIv+sUFkR7-Mn6}}(rW%rLs^H7PyR72vz(tyO-Vod@kPnX1G*)rfmqE;nM;Ou7g8t= z?MwG?Z`tlzo3;vU#m?8dywA-=G9u73e*r)Qs7(ZjKo}UA%cHXExkDoQa!bvEEw1y| zr#6C%%OnL?*9`YPHC@iCMBH5*Yk~70O+hF=5@opn3WGE^eo*XH`F3@!BF9y(LMhl6 z0CWR(X+R%gan1rf5%ygmLs5e%L?VFbF3_j`(FlV_!J*HLyi=>$a!c2e7B8kctB2B+ zEdPh_vy5EpWQf-ii0c$NXX?M!6k&4B7bNhvBvli|&U(`Y5Iw(7$klWQYs zWWf^Cry)U|_5Qh&1P8@`7rkoxv9QBJGlfWJWu`&?>EoJ|tjD8va9RA@uY*Y1a=aU9=5kw4u zjI9Y+2n<|;ol`AAvUJ3()(%he`BX>)-~?omadYe~6LPG5Ek5;S*>xql7fB#s%R_0T zaIikD*%4j6yM)78HcYLmNuJk}xamiF-ZGk8U`&b2L6)E*Z2ZnsT~38wW(0pw}iNJcGn|`5LH@6m3;k5gg1l;I1#j56RjP_+UZUQA;zZPZhc*1NA z^oBkb7;Mj+{!>2v3djKoz1T#Vlzlg z4g2mRPL&V4xdGd+S&F3wp1Ga~-ZQqbxNAB1?Gx!sf2MczXL7*$2M&$*kVQPLUOu;< zd`^1jBB*LoYsAjpm{D;lQepZ>rr6K-r`oTBr@NDS=Nx!9;Br28K#w6l_E~-nt?W}z zYRwVe7{eRdE}M3a2#g0J9Ox%xI)sV=ARTH4*OkRPrwl8>E`dnJr1XqjW_T7LU3$H% zUm1vHlZ1QBa;=h|XuAFmv}5BxWE6=rw>F33_$fkcl~*)L7zlaAAhiTiEB`;4H@Mf- zuj410OWv%bcqPcQJKvo&QtvAS(XFn6D-_az(~lqRr<@8vE(swx10>`+0NC_A*Cr#g-twb^fSsYH1IhVih+7568oYcs zTnn#f;Sdw_bFqD-lghsnkpAUtVRQu(}WEBlfzNRIwtS!z8)D{{Z1#yJ>= z4`=%OP1|C@b(|sFL8qD1%I~8v_yJijj~CEf(y;dXLJQ{s5Lo=+iSxleGtC>XM}9eo zdiU^{{~W{{SY$@KbX8Pth`vb7`b>cP(imQe(_2*Gr(zK3?yk>zg3*(z>6_j)A-}|k z2OHX%JM_?cW8K@SY>So4E>D1uj|3y&TZeh^J*>UP$A7dDAZN-Y%S7s^OA{PiYN(UR z`ZQJ6JC2uIMADkQ^AE2L5@c?iKZ}YO_I<$PS^T8^@@nPGWf*+J_$PjYYceK+R(r9F zSlkh2!PVL=rTVSpwJ#9cisT+}MxnCl$-{|VLERp6p^KCS-j@WjD?4d+*fB=4d!S9ZR8OI(S5nTlEM#Z2eW4SNCOd z^DGwqU-V}iFblCBmjYhgcyAN)0Vgw32|6eM41zpHcxU#2uUC+6r(LZ%b;&odigAG$ zeH&9IyL0zjACg>rA5Rp{81v8ctEXH*f!{A~5Q zK&AWsg2zXEJC9|aZz9)oiW_DpCmnK3Riair*U>-L&ked6-!7jv-IIxBK*?F*l-6Q168a44*~4^nyvU4TCkgmqsm zFjVNVHeZqOWK>_3hb#@G*V&!)7fZynH$k`c(h6`=0Is8*+h(?1yynij`;tL7m5c$- z@jtAEyGwiI`t-k5I2)mrSQ63>N6Ur)kc4eBDvIQlxYoT5_#syF9;K{VOkM4M!VT!&jH&*U3;DvQb zL$`rvWoub$@b3_2-UX&+^hfz5w*BrUf<{RhtF&b)GMOM#uBF(1^y{E^7!KMh(49QL ze@0Uiv`1v3_a_RWAvAH?EKDsrzT&x~-gffN5mH!y!V};DSZ!uuLYV<@Ky$TUv+>(W z!<@vb0iHvMepRL@a{%ec_S4{p#sWP#N2v z|Kay@Glrb*qNM5{GRYh`6q5?m3{-y99n|;`+qlvB5;>}e+V7m$vB%wxk^AxUr|STJ zV-S}1TkpT1Mv{T93g{Z#$(Sz7YdtGP-}313;}@EShCbU7(!-F%2Q#cYqo}54uoNxq z{p<#{i?NM9qA8j2_Q2ilxHii4@jgDzTw?flR|FD!T>x z$AE5ve$vE=+YhsT=fgAdOiab}Pomz{$I_!VkR7Q$$mmTmzgH$}9|j*_uE0dGnEC=ev(> zpp2dw-GhNNR%WcIc6zPG<^{Gn*6v$%Y>!%=g3d3^=&w@8{?Dg8cV_Lh!jcuH|OlitLlnEDN#k zv7V%oW;tJ}umm#m%Hy3;=k<<_}dx-E4g{*d;z~h8c$o^4I9b740m~=P4EuN z7EkYFvd%kKHSE{1=8c@Q(vs7KjPqUpHy>wPVi)`t64HQu{x52`jlgajFGS381f+nE zuHgdN?dD`u=f#TxP2q}}mbXacJg>5ohQ3i&s7x?N-~LF^lk))C z0{@NZ4&bu^mjhTLeOVBh`JmI-97t`*hr%`-Le+vUE>>qnjayk&^G2sP&E%VRkO~0K zX%x!~#gDV@(ZIR~W~cZi0=`x`A*6J1Wrj7qF6C`A7Pt1H_%BxEiq}q1^n4&_ERo19I;0`6%B6sYm9B}Ir0okE6We%I)H`q z-udfvy)JKhTx?$G-%P#Kmf$bp#PC1G5&=5;(fYHRx4w~Y0&`m8zM@CV_e~70kO-Oh zQTv)0Fc2U4QG=6MEk}mQGyxAn905dcU0=UId@e=ocQIdx{N%kAOLx!C5Bs$#$|26P zZ$H(On+;eq2-DgN{~quY({49AeZY|PWFu0k9@LH{=H1qCOTj0VrNR6IXe;la%g{1K zcBakn{$KmSm*)wKZAZAY@^v1-O zUY=&$&qNkl>;2ns!qb8p0-hSzDuhUF+;U_m;;z*FdZ)W4yq0V%ik0weNb>Oi7mhW= z{l4%~gZbvp;qlX)-0JwrD;ryD(@)&puRasodnxuChQ>LN8&V+N3x@rZlM@`QwxjWi zxpPqP+7m*?0;_nesC55-Iw%MuXa!q7)^LNr*bmEpDchBq*mXLlwvS&NRC`hFjVV(I`<9M(&c5 z64-$t`1Ug!TkWH#saB#XG3@?F_W;aFt*JT8r4^Hi8Ts9Q@r`Jcs=S%p=TGauo%QCE zmA?Eb4#KQK7<4oYrm%+m&sYbO((Bgg3#ls1OCXK_P=4dk$94DL`t&7^kNZ66GJ}6p zTu@-Itzt+;iTcK??}ClrTDjATd58YRO9_%UJM~@F(WAKay1SDK??Wcd1LKcW(y}#P{pDIPml_OEDS-c>e|}; z$_@)SQkRJe+5I)o-DyvJ3@^Lz&hQg3`t-r0j7ATLe?XDvVbZ)r>YB^T1`P6?q>o{j zSgclJk854n8v18JEKXxf?y!({0jpW*qNBuChze1N+2vd-QPOOoqVL0MG`X*a`_gf0 z4mLQ*6D@2PHk22q4x$3ZQx7i%G>>Lk?VK9DxZU{E?O6OCrQg^&EwOVlAEcRM9>Z63 z)RA&@5soqt?1WkV#7px5!6Ycq-P0K-9I#y95I8g(yW7`pNC8M`X=^*18bpQusrW1y zm(w691B97iWn<~;6zv8~04yfZ3=DtQBwq7z*$(O7RVd+aFoT4dFn(& z=vIg@K(9{t9oiwdh$yTT7&W9MfN(!VbU=1EQk2$+Cw9+hx!CK|KQIaG5G+GDFGSXmU76V>c`Jb^JMfl3oH^=U60h92sO_yl zP5y5GwOu=P;)7y_vSO|F&aSSKDMwZg9_sY;Com3x1QaCtI;?@wkr1>C17c?eIxr9@ zW?#L;;J)&!6&_EdB;?1JVkfMr7Rh#%L9h;M0 z*RSku3oi&obricTYn4L;G^DjT0Lbpw5H3ya`=(~CJ_!Ds1nO?ccCPeTA{J-b;<1D+ zM}yfcW>EVx3R$*HY=hr``Ap=~F`>+2Ypn{enS1v97ynBl0SN|-)*$(7k5U#z-Xuta zHWRe5%ZI!-7nkdU1^S(k`VY}0VJmMO_OI^y4hQ~9Jb^|UBKxee_bQeuZJAzHj zSNt{Tb1Ii^N4K3wioCz7CXK&Wc)Hy%f3RG*0QCk(E0ZT|;BGeoU>3f#A_&K?uBkC( z914&#tS(5mq97FcM+8^=)2J_TfI|Q{@L!}8IE&${?uA7VUMuVJOg}wa-NQ6VpWT|t zIi$aYuw$wJ@>~CdIYuykZO_jgUOYI5y@I)h7qGat{KVDv%_GjmYUhfwGL*xp2Cxdi zv4!;q%u|k)FRG9L8vqnEcp)Fx0x;znpe2A|0ohLWF{pq(Vd4CC%{R+v?(j-$Z8yUq z;I=H_r2$KptD&@W(1R3?Hz)$_0`{01QUF8yFx=|Dx?^upQ8CzaM?%XtFeLC> zjI}PcP93qJonXmD%Sm#N_>3$eN|F$HUcR@dkr5H$!JiJ z00j!6@cJ2W^?hB~s`AqVLkd9ep^kJ=PW-*bHsU7EG*pF0KYypb=~BiMWo}5W7E&APr2bXd=8+UyVAlr4CFJKQ$)34=W}WIK3=?QgjVoDHjWj-dfmwr=C#P=4UGeVN37c z%IWShcHVb4YR^#1dQPow;XV8#!>VJm9kQJmg*WhnS%Oz*DZ(er1cq8yoYL>C-4XJrAWWQUx!E*KJ# zP{yR@gBU-5JNz#Im*+4ie=#15sX-_z2u?SsT12XUKVU3+$Hxt$><$clSZBRm=|2MO z0k|JhwHX_S6TMJdI>k(+;C48T>wZ|oi0rW4cAngoV9+{C<9-(V!Mih(Y8jxKlO&VZ z955Uh&s8n!9`;G_a_~B6(P=0zN+>V47`HpltjWzw(o~a;W(pzY4-S?2d#31iM6kka z{aR7s>WOIOAwl>zoJ&mvUM9FS5eZkOrdD?+Trj6cn2u@QS3jZ9K~O0>3J_|T<3N^H z9g#Jv2p%c)QUQ}n`(+n4MT08mfYj7fv-|%-f7{kqa{c<;d1Wx2#Ea^jB$qF2Pn~^rDQRfk8%Lp|pb<5pKkOfKKGr z%1IWURM{DxZeq)%p{sMZ`4t{v<3?#@xLuhOmOsd8nM*4?Ma{hk$OH-C_s-61H*Uo#q(MG)PRn_aX z)(RZ@RmCSHBoA-7*j^JMdTAnLUV%9EHH>*LW$0*W<-2Sw0~>zXLO{m(5!=B^DZ*m! zT`H8mhJ6;U5fDg(q^TGg1$NE>T}qzapEDXo!?x_q)AXieF#*4f?sJ=uoRof@#uw`l zpYF6`y9e=Ht?a*8&Up(={;_tY_A`0Xfh`krIp~QpbBq_6%xTke=n)0ZuuX&t!+-h? zMfJc~5iBVfAwv|}iq=|?8ltZAzP_`K&CO@!<>i~{R^d*#MG=Pgt773TM0YuEe{{}5H)6s#HUnRK1u_0`g&1fPesj3w4$3`5!cBcv-DBjT2Q2-zx_7-OxNcZc=Wo=>#|&v9C7j{6+)0Nl$Mo+ zTQRB#sS*GsiJ3rgYH+ZVpx_`PpCAUfD?$C+}`5Be6&ndnHcIW5&7cEvpQR^B61A33S9}8?Ye&QT;xbBS|yC8?- zk=Kj)cJ@ta%sH#FwBp3oh`iuyu^f+Imh`pQSMUo^zTNIH-6YRnG4wcne*2|J^>0@} z>Y~vVwp|u)(^%$weqF)jt2N2c10ySY5xLwTr{&|POy&Rj3?LZ_rPtK%&nF#?LRM?* z+a)-OeLzvb;{IFb)In{ln6-a+n2CX?W*qL-JKw%=jrJ)v&5TD6*^8ZL$2ikRRiFP( zef)#^2bjPi=V-s-r0_HpRJ-a%MsGXk`mD^i1R`IV>rv`7e$35V8qs*!u z#jMvl;jl1ZCkIQL26I5?Tv~1Id*hSMIJgpL+?VHl;JyV48eVZYjKxd6IF3SAOEb!~ zEJn%Qj=Lny_EQV(-+iKJx7CuRyZv61`%GhRFU|A&!R#9DHCER4&2!Gz=MyeMYjYR_ zRv64VTZE_UB=9YI?C4LLgVpU`viGKA9C2CbZrneAN#3N| zLf>ULLz9Uouc&f#Zu)zS4Seq^#>O1ApNWCMc9?+H=noJ#51kZ^@Pt$Q?OibnmoBZ= zf4I`+JOYdyjHw^f(_ey(Q*`h5xlju|6J14^G9WkwR72={gg69v^Z$!C1I_;>40~KB zeVZ?sui=M7@^EN^*aTO(nwC}@Amq9g_BUZMq#?R+LHC6wzJ1Bk<)O$7X%P2|GBdLP z&)PqPb*_8yS!-aox$yvZ&b=OK2c38C*!ZL9@Wn#KPgsW@&vi9U@AloifcJnRrDDQz z;K7XJJwBO8jaa4Z$&;7oq@S6;E;;?WcYKIPlatGQ_4@KI6v(1>bz58f@b(t?Em6P% z80QQPArXBcTkQA_wa+@1drdNoBFxOp9-z`h3kKwapm?3k!oorte77>3@tF9Zhg7_F4_rlL#<;HT~l=NZ9uU_>4!y~dMSK0pe zBmvKz2p^@1R<^Fr9jgG@mN!fz|BG>Y6BY*HVIyz|gBDUlORE^lB&Q;P{TnJYUV!tC z>=cxR`~}7hZ~K>6ExS(z$1Pf`RGw}+UbF9}3J?18$2wJ#dqy}nFVA!NbHyUmq{MYP zt^DFe%rAuFL*T^z_h_miyn`cy$sytjlNa=c4G|6_97McNOy03pQ-w7vG$-*NLJhQ3 zc_KkvXDf7-o>?!_iAFb8Q&SQOwKrdz@CCY8^=dMpRbJM_HRBKJ8_n3eoYMy2;~Nd^`dqjVcEPn#bfu!Dc> zKAdT}xz1qPDln?cttgd`#G<%Vm|a!0ys}~jf(rPmz|09M^!V4%m5>3iQKbPpnt4#q z-~F}kzH>3!U?hNxEd&5UH9fuWv$NRnZ9*_2IMZ4|g)C=h$CjH5@-b*r1riZGtB~&j zR=C>{uS0ja3}JlJYQ;?gzHImX_RU_k+L1ZxmyTgx(L^@ikS-N=ESI369+9}h+1Ki0DteB*Qq-2n!tUi+)I+E0Zh}Fu{lIQ9otkoevv_UEx|DnTg zXKz+jYP|=C73RA9ny#@jn!L7r{jzFY#lu}QW%e>}xXL?NRW)e%N_i-%W51h}IGyyn zNTl6`Hyi+r3|O<;+HiRY5T0sNcubtsopny|(mCs!C)F{5p#cGspf*SDi~qoQP$?`h zad5y!$tfm=ftdzLH>6?gIfguUAUxr59B0ivAXtoSwf;(iVc zI34`FgHR)IokG+@77S3&V1Wt)I7~cM4Ge%+MA97C;j{q8(nFXErpqSU2b?+~tepy& zuHScgJ=+LqMl;UtsOm7t1aJjRzfml~XXxy_EtjErHuiG^qyG22v?KG{D!Lrwd1u@0 z`(6gB(UyEkBKzlY-k#w~=<*D2-%4ZcY&r}O0akAYg}Wee9vK-Kyh#A)fF(e9^V@AC zV}8WR^uk0jB`WL&znZ%G%QU93N+%drn_=~Zgarh6%{QD3oqk_j{6s`Bu_{i}$+fk$ zHN3L(Vl%O2is(&*=$#Rq(b;XUD!=1{n-v9^HD{%z_5dmuBQM%c4mpi`%HwZh$eZVyJ@<41 z=h4gBx6*)%o9pB|$`5V|(hd?E@Vho!@Z2D=76miu#ds?VFA6Y#P_cfl;Qlq;&sDTi%L;Wu56Jyk?8f({@<3 z_&Y=96}LytAjSUc`Z`gE=?lku&1E*@?*-jLp0tZH5MO@sbQs4hGv)T}Rf(Rw5MIUb z2}pnu*VII^@}~G>r}|n}N*$rrkCv zDHV+vfPQ*_6n(xy7;37Yfrb|HRF~88L5t-k}vG8^xg4M%5JZ0KB2N zinWIh8*v8gLnKuOtLE%+HAnEYJ*&*ky;3oH{P(z-vi0%Za)-$tAmTsee-)zoayCAO~k8K{OMxN~b<#dX}Dqrgg>%D9MDx#Of!<-FmpMSgw;oF&nxTKxl|{4O~iKK;HAI zH;Zbr{>=o)--?5O61Yhj7#L88?pF&zur{H%D}<&2Ap6AHTJBjVCW-B!S@+H3k}CaY zbjz5(?m}?o46nEsk%&P=DZtUFIu2yd{sD59yE~K|Th!I9Zw%k(o5%LW+Ie>@d(d^V z8}{Q#7R^_iSuXvcOI~ssUI8TpocK%x0pI4G0pRQ#91I!C z-m&K^3LnEgziB!&#~{-6SD8(Qx-6xVcGJkf^ZM11j9k+F0~zr#L%19v)e7-$sKoO; zAyr0cX*5WF*8k)cI`0?PXNiJYUwHecIui3C^P*zE2WU&d`tlp(jafFwUdRXmNC!Bb zVMqZ(*6a2s!t2j2tALUfUK;%HH=M#e3ec2C6THs_$EA?a%WejBU0qq)h>sN&aj?Z) zZ;LL*@y<70|8n%UhGb<*uAxEA`?T0wE3zS)V0?v3hAMm^M}fgbNi{mjU*`8WQj0Yh zwQd?~?|e&CHglJ^gMIEk4NV$3JS(u+rWF@Q!a2&!!XlfghBC!xqm=Q;LDp?Adb0O~ zP8N*?Kn)>fF_65khL-1mYCbDG*3q)$$^}9RuuQ;O4pt*h2!{G5qZCIM3|l;Ch&$lS zeIJ&^V`2@6maI}ZeXm>Cb6wXt?BiVh9P`DArG9r<%a>_iAo;>aj zd{?ZdHatK$vp~}d1)c2c_mU&u`&&100J4cbquq=-}QVup3fq@G?}*S^D6c;Su22)BP>;n!(D$!C!rGy-rgsV6AR zKh)G@JbBa@f%Q(osr+~u_Z_;`_4H_|!b!s0u_SO~TBbhc=PQ`rg1Z<3*FcehUQR%b zTL{IvAeaeguDQwM8vpj?!iKl-Fn#uiW8$$Bmt-Hm{TLIG>Exhf(Fpv3s28R`TbcXb zJsFq^07d~m2%Tj}PQnniKh{mt-O31N4+!vtkL=T@Pf!4ioJ=Maqhax+R;_*Vg2@QD zhFtm$q;dk}ksDIhkdYsc+{s2~Z6V_Mj;6_*kVzN%u;vxf_J2`J^ z`}i8smp;CmpPP#l`udFMRo{1-CANRUc$Ux7E#Q1l#CbO>#I`jV&Gs*bE|ly6YZ|(< zZTYT}ldJxhF9==Q02l+t2zD=Eg4y6;n0z>c@OlEF!I$)=zwe@jU6Db~PtCuMzIlh^|DHy&R^QI^7-ikP`o>KQSE}_!Zz07? zy3XREIp>@3r9q3j-4r1%WlpXjyR6#CP`3cG^MgAV4eH2nzVTCCSrxWgfQR>>L|PV@ zc2LWvxg8ztZ{ZUXf&=zbPEKlmK4fyBz5tXI1uHR$uF(%mQm6}sorEe}dKM=@{1)gq z@Q5=Vf^;EZx*59<>fV53g&iNkBG8Kg%rwA&Cjqacx^aeh>PKN=ga;ME3{c(lJxZe= z-@4x%fd%(y&iI7>bT;LP1iVl{h0cOP_`mfQ4gljs>2~b^)v6ow-%Ldf*~#tC8Td^! zE-E#3*6}cwm9rHtlAHZ-n;p3%V$k)SC_z-JRgbPjp}ZEK@%sIiwC*39<`JI9%Jtah zC8H2`0XIX~_wRBht&pKgIOX_Cno2;z+q))SS?$hvd)LAiacJw($`XB&?9#2m;!*{N zv_$*}x?uc!ifnziJFY(GyE@o;^y{8B#mAgP&MFP^X%ZAph-Ho*JiGnO zme0Fq#ob>!cCNUP*xR&Phb2Ub06sr-IDy(3(d5?a!CI(iXBFXYlayw!7kJhz$`>qO$wyrknPSY*(a}YCE;c=Ya{e^# zM2Nfa!*Qe#I)vqaOGGnEp4mJ9{`n~Y-VNA8ty=CO+?2ciUCa15kr`rR{>bb*b#dE> zqo?g9TYdTf17l-}7eTtpBs!(mD+69x`Kv>27jcquhX=<;SspGU3zmO1l?Xp`vf_=H z=X@?@$P-oy@`O|2Rhd0wh}pY-ww(ypNBk8qc>+Ck^S=ZbMC>=lSpei#If&>P=QCqAo!O7Y-dh*{&_|+Bbi|oK% z2(>OE16OZtyxXYQZuigPB)$L0n>}|K`zr?|CVtmaFI-bopV+zSo8!%bGPkE5G>T-2 zhJX5HszZH74Zq2kEF?N$f-}D$tWLJJA(KpQN#Iu9w;h=lmL;P=&0o!X(C;IJ;P{K+ zi1_y}iQtGYk|bbl-0Sis@}8f(4bgPo^(3U)Y|_%sjUmy3e;?VdtK`7$y!(^;_!D^c zFsKO7_@%!;nD1sQIcPpDVZv%tCDnVGO0jK6;L8zovk~f0Ov;tX1$TYSS88p17r**c zdY6P>5YR9%-~fr0k-} z$S3*@bO?a!_udfqv?tsIuo*|gsk0#LgHuC$Cpmz^9AW|gFK5EsjRKH6b>Ic zl`mw#VxjGtlX{hF{#wfDoGAvF8Kr>})$jE?nVhcdOZ zHy&zcnSu9sH_+LWAi8n{Hy{!9wt^}a;zNVl1J@Y-^f(TbZESe32XSwFd-u=iU-!n^ z2Fo#v|Fbl{C%AX;EtgO{Or%*U9N4eE-YHGdpIr&GXYb#S%2>tlW??Pf7uELQ4#)NisHh-CfidwO1zyd{>3$aW|Qprh)M z2n7g>Q4p7AbX;6XQ4vfIhZ2%^O|P_s6HwWt`t#`qT3mG4xC5f2sqzDO!Zc!etOx(x zvF3_fI%Zq_H8E8u_9~}3`_)1{MuU9WT+R^xHWdz=eN0oFFXv|e+pe~LR*tpF$+h>J zT_vj2V`5@hXrIlFs%YG%sIT`k+xRv72aVI2K-Y0PfBACwk^Pyys1BFq-j+}*H(UoY zr ziPTmg8BKF*D3Ja6clp*i8=DNCBBkO}%d)4)7ppmhd;SJ9AGi@~A*xD#GQX|Xba@-A zB1gE=f5P;4Q z{XlcwV)l2?tao&@4LVgAFL5mg3gr+O4?+SF_|Qm12;gFQIW?6&vNGd#3{xj@{3Esj z*A*KZn_p(@z-bt+Dc_8sKm!>txBk_tWNBt-T*31 z{=C{G_!)qN1ZfrzvZWq3S%=deninEG59{W>?Jp)>AVDUC{~PP6|8(%UAChaqd-#(O zd%WBD`wpR$!GNr|HEy{mmZpnHE(~82KbF8~yR!Aq8h^HG#qs@bOQ!k4)~eWfs{Tyn z(XEv4*I=GGl1oc2dqmc6n(~*xBhYR|yy!gnrHm&yVB8#F|@8Iz88hoZ;hSLL1 zU6=iF!xY;ZrqvPQnU^t3I;!mz+n;`FPjN8Y?IXLK{q;ftK6r zHdrepMOS~ayjrof3%lMUXnUY&#i|Vv*&I<}xAE^U9`!U3GzBKp#H0;kIxQ=UHmje1 z{Q1SrjNfnWa5S)M_^4RjB~muH>)^t&FZWDY&5@kii=Dl5$1WLZ{LSm#r}w&`Xwl4w z_j7E}S$jRbmL70ccUz_{et%m8Q3qNc$(9m4|0n{uZ$`hVmYHBR)kT&Hb~k_xy()eT z?609kIW7C}#e(a>j`AC(iTtn1{SvQ`RaT0*p3FZA-Oin`BGazeVG^c7*agEyz~tCq;JfvRYq_ zXQQ#r%5&tXGz;Bh7%1GHWZq7Mq2P6X#?kqt-{+gD4zPsehDBHQ=)OFkgDHaperzHe zYoZm>?#Ituk9oI)H`1x%x2mF6CX&LlzMqg5^DIiOo>-c*F%a3PEqKJC_Je2{J9KOH z5D|w>w7TOAD1q8JS@Td!_+BD{8DA7#`3w#&!uReX-C0rhRhUTY0JevilbxsiiHsgN zOm1Lc;tRT){xND4`iDTjrQ|Cmqke23{n<^4G9A7k(`k{VhetL-n=LWNHYG@QK<9vr ze2g1-5I{E{!UOCg4gMtqi|s&Tmw%f6i;J~eaO#=FMRbunW+F&|M4%B7^9hf{1Jbv$ z;^C#}{jIho6hI!dK_k9fX15>{r4{(|5XAG1FAcPm;|6E%4xPO9H08=r;EHG0-r$-y zo!7f^CM)AQyHf6cygrfejhb~U{kMut&!;a$RWHZTuf3)UD=KYF;t|aK8$lY=H-=LA zyN;IDX{n@)oSej~DJdYA9`88V{PF{7X2u3}MR=os{D?YN>GPEy(f^1xSU{Y=@|h;y zwy6{9Y${UPS9rwFc2WARN{uL~cJXp(ep7ms-@7U*SCZLuoNi6w@>B_*KxcPTbwvAy zr~d3mrQI2Fq6ME7jR(Z-MTbLaNgM{TDx`HLOE9Q-Z=v+J>2!U2lJ6Z4EY%2hz{?W{ zdBFEFd*WK0#r&bJsqrAf{=&^DiwF<`9F3EF2@bJ;fA0lQfU!n+DLZB&*ZKJlgGITc zWr})-ZHnh{$5u`_Ju^Q5cl~(2&?eL2trN_$OfF%U;ySTr<$`S=%Bl6BuG0wnSq@zgS>A3F(*> zFn=IL&j7MP7z2<5_Ii;8+ai(exlC03k>8P;>TE6G#r-s3f1Q1mjee6`c#&6%uN0I>hy1NudjU36Ths7|9CNZ_semZ5c&-MsjpA_)531)o4+JX z3wIlk6>rc{E5+!&FFYbA)4sCvko2ud$~AZK57As(1H?DRWpCb37XTeq?%;iU`PRm7 zqQDQN*qOsC&7ZHh(m7_VRIwRZ$M$xALL0tp53RS6$tJ3kO#J%8(E z^;b=rmMDXM_-_v+6xx`E{;OpUzO^EXEMng#2v8X?aI3(E2;`19-;jEN;9b;kU?XA3 zKQ9o2*CmKNgeXjc{sp3$QCrK^Q!+%%a5-N z6gaOc`Y%z~i^StI!FBcp4<^gUaHnQwgIjfd>5e6%go+k>?0a-K%^F=D$Sw%wpQk4hp`KQJ zzeTf=TXSsgdr72TU|>>7xm=%ZlTWp`DOp8 zqU7Oy+4s+@@-7GEFT{Ab2HWyysGgGV)i=CwY~<-m{RyYJ_cF&f#riX+HOT zqYCr9dScEePE)T*MZo%v)mQgmJcbe)`MNBLS|zS&@d;-3A*>}8LFrpK{73CRulaShIF=xLR3F|Jud+{rX#`6U+ANipreASw2o#$>l?aWiNy>NneF+bKBY4*aIS81#iJE4JUS97!C)@D7?)wSi zHhp;OpEvXzFTjVKg0Kd{i*%f2n3^C;87;Ed40pi?FsOf$FvSsl)ITs$BHb7VHqM!+ z1qHJ>3W?@F=m&6+`hSN6Xd2mZ`0u^1>k)uTh_ZO2a3q>nj8PxAqIs1_*@T@058BJy zi_6Q(u`@OR!S$M}jf%GR;g*M-7{4pqg!I+`c;fge5>4GiG_3{SfJX>Z4}=pTb` zOT2p5f8KzS2b(%3_~_W!pduZOer&3QpHmi=_|I?3f-$aOy|A*flHXj^_rYpWyIQm% zGABsEaiOeoCsRD#7b6r;VR(SRq-o(RWE@y+XD?Ys=($bT4KBY6URbw@(N_%AX}^9f zu;VdnP_fM@m6m_te1!AjQB`&gv5`X@lN&QG(hn345XvMt6J%0e@pb@47MBt0TsmH4yL20URZ_LlPTWOgxinW6Jmzj*-Zr`Hnw$Hvl+FDy7rHf=kOU|U5`=&0V0bURI z4d_7RuTYKIYIMW|k=-?D^5RvsBz2F@Q?ao(5rzT6F@+BV029P25-25ZvXu@sGPs$$ zM{VV~eagxFjYLa(ow|sQ83i3bx(JAU6y@*Qbz4@9!RgsB>4Llzz5|a6Ol$79Ouw>K z$ZK^=tD04t4eMizRKSG=YBGAs!v3b(PW%?BpXawZQY;UZ@83y7qn^T#n0H-WBaKBazOaNL3G^_ZurRSK{jZVQAAMWCz7NsEq^hdg zVC^iTk4pr@o;#Gl7j&B)OCJ^}t+9zp4>3p4r9-s~d0D!VI@x2=LM(x$FpG~Kd|6^5 zCs2N1zSNHELyF${6a#~5a<=SYW!9I5CQ^~U%{Wjo!@(@dY;|y&e3nO2@cuUtnOG`!I^Cx)a(*Hcl7tqTPI^J zu1C?vJ#SrTPiO73(j!USkmh(qnzMavp#0ianTEN|Z}Ph}?6m$aUV%wRX}3`Qk!jtj zuOdKC^SZ{-Uh#X9L1O>;Hk&@LT2qK06u_f^O(W7!P#0x!@4(dYkYley#Q7gyy7;Cj z;Zdu@-NR){LzM?lT+rWE6GIBb_aYD@PbT4%!C&%Vf;uE%1nmix9uZ8;SD4tD>d=-G zRoAE!Uz&b#aIy2)t8N~Reu<FqgU^a@^Aa&*kBxN6$eD`+3_w85R5t>{&<*vNpiy-cMM2ArG@Q0Nw)b zt$7U_4E{T@2t$RZ5-*)t<0HsdJve14T$OOV2gMx_spIb6Q9tJ*jXR2ZvmB&|_}kmr z@niE5b@^16^4*Nz&olqs(VLHOWgq05L0c&lEpux)yfq=xym6zJ;%UNMQ?*e|s-$xB zj$MK&b1?;Xa&ll&vG{8qD_Us!9CaP34+Qj==H2FI%0wx5P2>(&9^Ea=)b?~yze88A z$LeqO3&$k+wDMM;D50PB%+jAVo!-{+tBD|(aAf3ZoG&92mdfqi6-npq_@}L`YBw5a z2`P&#qKdhE*AMeFZ1306c}jELDpcV}*?IY$)NHL6cE#ozu*_yg$Z(nN+s?SMUh&Xs z`E|fYx8_qEr^&M3QX0j-{>Ga(*T%{jf6`TZBEY+)w|}?=7&umdM*1g@t@hxP6B2%X zaE$9$Rbw@OdwnKHqo8Uo$KETI<4(VRJ9F-_(4aXZf{OCS&!0aR-)GU#Qm{32^$Y)M zR&u)Kv%FM&EJ@YlT_Oc;1u&3j0sEGfmEE-fFV|>Wf{X?*1{j1krF$rCq)W?b^b2Y2 zH`5eqy|Q-w*!6*9@rv*vm4q)XmWOQnIrKCYXEDbsyH>FPeR50@u$ z1sAX{rl!u}w1IlTZEaQqf*J7lwGFw2b?wCe2JSpWWMM!8M}$+o`!jnKqCEUXi6}`z zEzf%>vRp3M?Mv#Bcf~1Z78hm9ukVqRWFcR zdFOIpi)}8BS>a+KcXUJBXz}LG2M5(WcDl5~T_y#$*7Vv>K+u>_4jxxK7m}Kk^cWog z3J0`YH1*nd)udik9$NDioP8Sqt^2=VSThIa0^=%q{DvSQP(RW?I;twfwzFnz?8L2W zR?A-uI;WZ|J{nYr5ELt|ZaG>GPZ$eF;P`aEj*RoScslDT#># zC;C2nR@W4+z9}@#diLz0^R3^^Kh|Jkwgt)c>q!V252!W<{mZW;aQu z=8t;)68F*~Neqwrw*<_MRy(o-JQU_!SWuCveUhOjAa=7=o0D|B+4QyTlfW{GCzG~5 zwtnG-Ek8@0AG|Kt8+VE`@3cWc^^K5~l_P}qhPTVdS2B2xM9$oNSXH3sTHF1?sFsDP z{&U^f!!?bJ2w?_J5oo(1UGZg3$@CX$5}t`n2=;p8sq)gk#hKR}+8M zA|#AAY6rJQ=84m=UI3U;c-(t;YuMN(C5WACCXDNSQ(z!+-HMb;LW_j}rv&NpLDMm+ zr?YeQsmF(d?r6E%*Rhgva@wb+4nS-EC_kS`l?*Qro)44(;7x!6D4@Jt3V-8!_wLDu z_|!~1Fe}~lJNK#y)3K6W_d2e!EB<*{@a5Sq<@TYlN0bLixdk*_TMq@16=NOwf^geV zqV07Dn#a8VNZZWB5X%{q?t!=~`sP^@)Dy|%eK|R#*&&e9cgnAMxd@S*bTGu?(J)XGB>v?2@@uR+6~) z-m{~f*|ay5i3uMW?khk9kQlwSzU)O&*diLHCH1;Sk19f)L^_zp;z4_b`g8c!JPBUj zLlE5|waBz+09@VApM&S$Capc8GtHasRX+yW1J7Lpo58K&TIa5fr0QZP}8BZB5Uxh5#8uk(*RoKdLhPY2QQd@lRJbL_F4BM+gQ{3OEXFjEgU#gGcU>U`A@)vuCBUabU;1qIr^9V-+d;XCXFTT z(bA#wrP`{Fl2Tgz640WyZbL9Y=x5yet?1 z8aj51i?xRf>^OtN_H8O-Hv6VS8jW*i6PL>px|gH6t}*BJ+c5SazkgoI-MopWUj>?& z&;y&(laF7E9X9>V3VOA0SWrLzuKQgcO1<2TuT$UCFbn+q`+JE^2OCaEXsZ$CN(74Hyf^aw)t@@`K>67y z`Dyqcakt;~=L&rHBu*F<{q4U%9ZvN(F-lK3;9>%8n@A`3SIr=KnwBSZxfpy}{9C3G zpXrMI0p1{|3Zs|z$CsGE774~jQwIMY8#lNv%MEcdp=S22H#;nnNgKwW9Bac7-f{-B ztA)j#wzf8#DTjsnOs5$q+T4yAODMZwEOhzz#~Wu(gSm??r=H>dc@>SSzDp+YHZ>7Ed{X{1Q zla=2{$nD;~H2}B}-W!t|Dj^vGzKh9~F@l#rQmB^CFN?G5{P>}Cf7`DM+6j!F+O1{V zdde&grk(FO9B?yWY03UVblh%-%otMdx#T4;$Cc#b2~Z7q9msq;oz;M>LKw}xUJqWg0# z>8NQ7ui!|ztm@Kxvqz;4r?38Ao#kje-q`ndpQ@j`NMZ(0YsQzKfAFABuXw5O>QGw8 zZ&uY}*+DucF5ZOH3p`%uGU}WBfzcILR<;uLp4jpf+n-lGu8yK^m)Im>WYaWx7|Fyc zWWRUIEel^EBZd^*xW+RSNs`Z!4D630Ak^88yK1(}=KO02!yrA>syIqZGFL~T#d&RfSFrPE}Pkl#2Wb8&=Sst%J^-z$|ro4a|HyMsSyLax< zM9(gTl85X{8XKjC^>K3Lo%@S^$mOY&~$3WYm*mfQ3RfCiAWb;;Dk7fWKq_}@K*2mG z2M5$Z4}QPABB@=wDUw77!{)i}t7>OE{0^B4#597k-a_?K`UFe^j~^ej7ORr{daXI> zw(h3xJt5sQza9;GocURqGPw5si6lq5(O>m`3Bgl7Vo_~3a`@CX@T}bq+5h_AKMZ4# zMIZ*U7R3gH?-AmyomkAt7TGiV-V|g-ZqA66(miJOROI$^0Zk37H?xn_-L?03rSt9M z*sK(*tDUWWTKVq0`v7GB2os21ym7JmnO^mNyx)kgAW$s%k`Ld1;|O_W(tHJo8p1k= zWtlUSc#I(vI}6~tOG%^`o`KXGt8~~N+5hd%U3{pkJ42+JVyQw)u|>k|-jKtFPf1K|H{kjRa<w>+ZsfWW# z8vm2K^qXp8H@+25cv~d!ZEVhJYUue=w0+YhF^;rbXufEgadXYDNve4Ji-}>a#80gw zg2%|!p?14qE=$$*TpxukoKM90Z~VujhR|}4s3|HQOT5qbTvSNt5g$FUUIfUib+oVF z-=?_V?pkEYuy(A8wVTELZ9XhvUj=<`3)88++56b1L(YMFFLHeG4F#xcXfiX#nwK0~ z*A&Y4a;=c|wr6=+8L!1xT*TY@n4*jRK93NO%-;)u?4BPVu@x=qhVvLN9!_}|X|4lY zBQtIUI}h$C#Cr?o#+jKIT&OFM+0*}hD0gz9cQ18b+36OHsR{;qG4YAh-&m z8G_ct!U!Ce-d$}zY`J&r9R*Ku)yDjA+7ZbnS&nYZKE1e4_ zHo{~|40EH-Wl6(%{?0Iv!lsQ!T5hMb*jMFQd-!mpI%WuuCQ+#Xr4(z5|1*6D-5$^S zO;4uueAljnphFo0k&sLDVM0y?alHI-sgozqVVJ|fpT1xNoo;J!Cp=BKVX>?r3W!L) zsjf~mKdf>fa=XyPbD03M%W&)z9*B9bf;_whyhZW%Q;{U>Rv-p-kn;tHdQdoS5EFuqbPQi+W! zF!&p{DiK`OAZZl>nh=0td_*!|B+JdGnn-2`J8%^{f+?c|M!J=>g~B$KkzMaDgo z-l|&CaMSsx=7pcSFfel9lfLL^+i7Mx|2>YU9i;pr%ViEEX=VkOpJzAUi>^q*V}M+C zK9=f(?R_^OfQC?&(2f%tlFMbWB*M-FZ8^yE%84b`hEppC%sulm`t1Pkf(|7LXfX1C zYd~=#73OJ_j|Qf68@B8YZvokKK=3J?smi8X`;Ue~L2j1`W0)#P$Hwt%6VoLOTdeCw?7NzxX}j zD#rsyc)Sb@5?t1p0-6v{6(}~JQtkH6e&}O~n3CY4??pj|@tNZ@40^BZw9951N^@i6 zif;4SU$|fX*@Uzy(d}5uvm*^lI6jY|_7v8#Q>qlI#S}&i3^sz6A?o+r2bNkhwI0(r zg(rPoI0`IZft~HP<;Q$uns@_4L*_a=#FW6UiPx;sYm##M`6bum>qqIbNcS71GTpfE z|NdR+Imy-L#pR6Ow%nlljkT*#qt6TLjn2CX$(IH?laCm*r{2nSyls0*c+ha);Rdp` z!qdyK*PAN0lSz;P0;0Brd_~^q!-|(*{#~aJPwk}+MsC5_(U{ZRUKiw)m)=+KmHX<5 z12}!aKAl}jn*kY>6devHwRP;)k!$jb3OehY8`G_~$&5UsB>Yb((Lbg%R;=sd53X5j zPy^towxaCWj3V&&RxZ0lscj<@PTwc5Q{UIgW&!F)sMF5`aNBf0q_w+}(=YBU7W^cR zh34}n*<$|_WNWSPA#J+oXQpD0hgB6D2db>40^Fok&_d3{aP82j111A**wls-9;Rf} z=H%dDcLug*D*4RIKS5DZ_a12eIR3^U5-M!l670|j z@^G3gw21xJxh2YIk23~G5D4&8t`Zfb_~LM4U}u82fmPc0oo?vh_LP$#R^X_jcUS4> zB}@aii42rqkEfQ%zXMN;b;P6Uln{;(US4G7p6b@r(T#zM6Vk{|V1YREU<}4tM--?5 zrc9@D`}^xEC@b9l2lkAwpZ+vI&;PNYDlV^!eN&#(V6Rv1#HWcpxjQ;@?5N)!-^Cb^ zDZF8Fwrr6tRZ)OKJ(HIYSV?%x{6bB`kCFI?&o5Un94UTV^pN&cW^Sq8OFX>07;hb{ znRvB6KuS;#!*Mb3sp;v?M5X()UY*urjln_*>V&(>*=(<&$DIf%Re{_i-0nwMN}{xF zjJNLg4A_&^ANs-NgS~OH%^r)TEjjaI1@j{BsGp=5=#>l{SPPrx%^RSHvV>#iOs{+a z!-B@msIon`pj`d-%@d-EL$k*)lS6!iyGK`->0LIz#dP2B@Wlu%{sNoR23_r333+h} znp#@|;#zIpM;42lKd*dKv!s^EGm7rdGx_E{{d$bn;@61CpDxP#LzI`7w=+E`s4&u{ zRj0uhI4GU+nl_4%Xn(7tRHmtMeLdrL0&MjaIfm=eUAADc(#pzWoFU&J)JEualI5l? zDGBcER#wUCi*7$ska@P~SaP+>IdX)9=YVnS`1)bBcUdIcL%pQH76A#*qpi`uVOHjF ziBPfLwI}6$drSu-*g7<)Cc`Y~l-wM0Hp^M5G?9eBn96%NQ>cN5%m0STup^h8C5`ImbF?4dP^_(OgD~#s(F%tnC7xT~hVm}t{()o` z1wO=jf?9Aa4XoUPw@0$W!ovFc`|ph{&cgL<1-_J^Pv??m25=ZcJfNuhl2Ka9$`uUC zS9Q^`OS^xWDXA`&1g%~a&!|y!WisfCeWoZ_qWs2W@Qg%$PlCa=%&zxt9NfCaB*Pw! z2*2htO64<)G#8o#w?t)VG1LqhiyS@i{5jPZg7Q8OTFR{Ig z>RT1dby(ljR@~K7T(DJZ>BHMnF~y-B`=HgkGG=HllIzL%0n^Rf1` zYMiDu6K`!xMiaHO2MU*tyF4kZuhJ?U{;hnCAp~$K5O(aC##=6E95Er0p?0UMXF6`z zE@n`mdRkU$w*Y5V2FJjpJt^~kt4+yg{xbK=&K`(tJt8Nkh|a{Orh7`G z9btpJUcY(mb-Z^sPD9y0Uz$+add_cqX20EJ-4$QQ^2xJg1wIy-;Mk*2cT!#6$uhd= z3HU_8a}OOiWBXg$fNY~FHs@uS<@qBKl z_b(cC0JjH0NrU+i?1d>ig6O#` zoN&BV)}hq7*Xc$@Fz9Y@-9#RPqazQR^*}=W7cg2{dSUxLx8pW3zc=kl_#Q~NYr^R$ zD0CcAaz8)p{4aeIj~Q_lYU8~`)$rU}WS1?met-_c$%c=FOd>+tR{nq@Wl>DSU=Kks zNS8YuGg#Pr$Hr=Guf3n6zOYozb*<3w-?HYVj5RjuScW_c`Zh6*Z$Wbn$(uWG>FV-i z@m)>~(iqC1An&h^ylBpA9XzB$K{?vUmQXM{`#qFPibNOQqIzpX18ob`o9!N2^|N);Trf|j{{T?$Y7)vr_|(N1(^=dUF-G-tIpX$x^GzX`G_nflZ? zm;bdkbeNU68x~NEd=|*+`c3LE#@MNxu|;2lSexY(iYK52VVQ&DZo5UO9_JgDRPXBfm3HF_N^K zo|#V|Co@eztzm1pE}K({g01H>7|5T&kcBY2e<2WC7elSx&QWEoIqidxgc%dTBBZs1T4s50ZA zzV`g-l|&^F?dh&jD?dIy4zKk6TdiL@Ec5pF5vwi-2B{NSxG*v31DO4?cVqe%o}&K( zMhSZ2)V@<<3D$0I#Vf|5}B-T{bv6 zoa%_iHc1BleMSQ#wl^Nw9(jCW5E)KFW39Ggov*u)l)bNSL8FGHpZ);EETIwTi`Vwn%&`jF=&h2f6g;_E(f3QI zkPAj1L#Riq;5-} zj~x_yXo8h!9(?h|=6VN5%OMK# z7>Zca`NZ*9jpMOG!TNxN#+sL`@{->%H<^_6_4Nl!*;5~^b#;+#gAY~5&@g9imT&uN z$A#9OkJ_VSBpvP^=ghV?jslaKhS1&j?$_kJ9nHMLoRglGP0#s=@73V}J+ov<4J*j? z5$HhpUGY_?r9$b2s+69-K9F>lV75JELOW&zT$F}V+^$-Q)xQ&!86s>*;G>ayfH+Y) z+ZM*W&Wac{YMZPv)pO-?cqSmbCB~S}0-y*uO2A0NBNR+G0qKT>M5&Ot6VoYmu>_&R zw~h7n9~BofBLGh->A7Rtm%oXHyd7eAG6--MQC;q6IV5t5h*sdMSIe|y!eB^2=QHvJ zuzL}CB2c6gSF=YxE@0q7gc=f)JWfmtuBy_~moU^I(}dk5Y*zk<;++`LU`fM&GJSiN z+Zh^FFIq*E%AP6aG@^RMajI3_=jc(j%$A6M$^v|fGbcQ@@6R9la&b^wvrkBKbe6VD zT;iYR|dgYNFC;qlX%vml(UoInvJMx!2JneO1+CBF}_*lDJ zcH--OcJhy{42tr7mDwUl9o`Mq4+IU(gU%ov$vf(l_w3noL04BxTN~Br!wFvZRK<^$;ROZ9F>iW}?B@{WKYO-fFpA+M zRWs+q!LxR`$1fIc&D2Yp&NuHZm5k7{2&~JQc%f}E(Pte|hl9S5pO9*AQhsIW{T6e% zUCHPtr??Yh#~Cpn`!5H_gh`3!8B|m9@vodW<$hsxR%cSjHPED7s5>dGO!rw=o0Typp1t>OiYZ3S^;cC zJPJ#+IuQ;--@2&9m;<+mw;&zz0Me1mztoJvI0y?8uta>nxcm=rRF72qX6#<@q=QvWJo{q zcYemZ@n`4GontUb>6l@zF-+=$a1KQ-;%G%93RA#Cp|&HVq(rCkJ5ts$zBa&3OGLkT zdIk+w;S7aA#^b;V0NagCGr<%p*K&{kx=~Q3r+>f7#=y~LLhFbzGm~E5CmV^9T8B?{ zdGF##ba7|QLU^9s$ZiwzZu34;qI)CXKJLWjV z-S?iC?(dLlvYHnn!lG1ocm4>GRdUs^=I`bVd~c+)E#^|i>Tu7NPciE6ZIyggylbe= z25LxFCs`Y`w-oDB_!-DcC^m97bC~~PXr88f=<`VxFEzjVWk;#qpsJwMC4xtw!GXOM z#zXqWjKh~CW)1rJ#L)|h#H;vt^Z#uBX(iXmrHy1y`&V<{S{mL^WRG04n{j<2Y$ZSJ zR`f4NBSvPFukHU5M&z}kCx6p$r3IJJJ~v(7s}nC+Ig2bqaRh-J-o@gxJ2&v*)6u!& zfkFQWn-hYEl2jjOGxuIjY-=;PAE4Z3Eq-~VHJdXhCsL=g?d)lt&;q72_R(3_*FL^m zPwE&HZ;7!hG1Dv<(c} z?rf&TJG3JYqNKd-hDM|5V`*oc12ph^fD$0el8K}f5;Mr+)8a`#T`|2bEiJJ&kJ{2f zK*9Pl0!9uPzSNL63uy;*Jn6k3i?>z|%7*1_?HlU8Sx>>UaC7|aTTMsD{0GKIPS}CS z{L#Jf^Q2Y9m^Wk@L_aIo%Dm3fH+Rnkr$y{Z$ zwPsJ;SOUBGS>E@N)c^X_?=>B0xfLqAi_eySwOG}znQZoAZu*aZFw)b{Bk~fN?nsUy z^nidk?%tvB49I^ZY+O=%`{&I;LpgE3{=~9c8#o-P)f2s4XjFyeMH` zemSSVDQ)INzHy{O$30UzbU}h=A}F2*$2taXJ%r#1S>!DBW=GlNu6~k0r9FOXgjxo@ zlnqACQ~S(Etc-2Fyk1s%k}H*0ztdL;JyYv5{9>0;JbJ~wVnyKojGyEus~M5f##omne@#x#>v2&+b3@}GWrU=Wk>>p6a7s@rbMxB}e#ocw6q{?K7PqUf zPjHV?-#zDP|I&VOJJg0rU7r%v(jq=Sb+0l8;SACUw*tB&pvS^CNS)eXy}wi203u6W zUE)VV1qR;>N)1s84N+1BYpK0(T4HL|;eG4>f?1HA3>wkmIwHPaA$q+HMcOTdLL9fC zfEs0{mYK6Nk{8Y(;I?t{u$7e+u+v@88#G3C*;gU<0_y-{m!C)_PSGmi+v|$419Hm? zM&q$Ja;M8@^YdRj70`r8YziUL%E2l;&B;ke?k*_Vg^#+P{AM)uu5a zhd^Ct(tcJo6F#XQQA~Up-M4s4K78}SS@Ck-!wuPpaz9Qv)35%#u`i+CtoFcJ`47Sp zr`XP=-|!1+FtyX(RC7;@yD9w)ndgDR!5@Eoah20T${81RD16#OM&Wqf{G}&X-UMCc zTT6~V)v)lDNNxtrg^+J{lh;IQ<5A~2Rq0~uT_4&jlQlKDPQKo3RH1ERB3wL*FYP7G z-w$m&L8{&H5-Ol&$>kNyIiR}g_)NaJ`tj7@Y3+qEFM%Byv-Vo0B-O^NsM zBR+xP;3G;(ud2LDQkyfVn~vxni0ePk*rKnY!^C;9q|@Qbzi**;SYqM>yUy#HG>do3 zc3?G!9FGZsdyvI=oa#Z}!+E>XAxn>3r#U94<$D*stCr)2imo+FIBcUIm zbLX+})i+P(J5yKdEaazjOzmU(V6BwurNgV;k@OU4f##%M8>f;{#POmL`HsK8cdcov z>$&)?XACz{lhgueqO7h2VTRY}qaGk=dC$vbY7KJy$L!Hm3#d_uL0LtEZ31ecRBkz#j+J?_9yH;M_%zc0rm0m#-3FulnIS3giyGaH%To@ z?Vitj{l|HvC=$|r2>&3(Bg{g`vVw0$MJ7e+cEkk=6+J4k3JN9vjAt=7g7qwd_&)cD z*VnsEH@u0tS7^}`Ocx=*wYBB#1%a;u5p|+3A~WsICT7|Id_P)w#s>vi--;Z0s zKvPlrT)8Uy(6~3gho$O%lLf|a*vw%}dj>lv&}}fN_&(vwaxuGFGXW&j4bKvh;0WZX zScqN0SD)4rXlH`D8w^N<<9j5x%&mV(AWx3nrOTJMK&uP+G?4ssk3`L^&==+= z!F*#L&m*nR6ftX`mh}ID z^j(zeqPp%YlBW~xS})IM>PQNehbQ(N6y9bhc``sw^yG~%+X3J{222+}kw`(fA3nGl zAd}bbii4$vtEucosS~N4R#JD8{IynmjG;-7MXi}1kx+B;WLAlXl{ILO|vexBT z#0e*759n2ayxZSiEu&R_MR@}g{vI$TOyhT?#}++7*Pc0hHu%e{BWLCD6MQZ;4+{RG z6j<1EIcU3+eY%OBPFd}sfB>_YwPdL`(;La?gU8%Vj`cN2B*`a@TzGd{fE9vw6c`GR z2L@jYo;@NE)QH>#%`6=+Y9dw+s5SOYEC>+Lk&%l73hxIt0jy=kUjz-a2Mx)jNl#4d zov9l?Q;GO_>}=B4md1l*9+kOe>2V&$`Uw&jn-Ai^(-0#Mk&+dAvV^Aw88ONW3p*#g zG5*06MXjhsI6Vss!}W!DWfs;=KDq79G-CQ^nbP~0p4_aGw6I+>hz z=t0c{lAdQ_xnV@a9}%B`n^Qmju|SYK{=gL#7eD0Z8&zoPQ|i|j<_MrwGy_30Z{NP9 zq+PpCZCGb$`MKuCwi6dGb4a&uymOiDy&$3C>;T0HEqpZKn(lx*#UC6#BXL~*&?z)j zhA}dwJq@CeC-<0c3PsvXoc<@Sy`p(}`BnGk99A`% zSJzdFNts$D_OCzl^@lL0ncDW#4_lr6c~*x7+6(;MGwbTY)Oioem~`>77{nrn)e=I_wWO<@#+2VTcIv+qkV&;}~$YH0o zCUxZ_ak z=3mhKCZ^(z=10%tgL!Wbu3cSL=0)KXqS57*l>@$fU-fy8^?`_|d-td7-FYLUj%#&m zd#+r$g2fX^FK&5^Wx!~*?1_i-2}V+gh4JJ;LA}{SqYbV)DnY&uG5i|)`z-I6F8>tk z+Uqojw>M;#RB^i2KIbLKm$UIK@m)@{Y174`}YElZC10~uXfVeW@Wib zU%lj!v?De@C$YEBnbdLiXR~Q^IOB=%1jE9d`wxuTY45AG+7`yYI7dC9rhhyxWLQc3 zuH{;A^)VYY^0TVwHK729?7BevLw4RP<$C%z1{k{{>`W6>GhC%j1_pNWLYA*roz5<>>qB@60QzHNzsl14;V z*Bx+I)bCAPX*r)BkyQ61@?u#^Uv0&u${3=R>F>X>{Y*_aW{1f`Ku+9P9+IhD=hHXdgNi_-188nsk z+bEaQVt7}kmh)#GIrB_Sc9 zeX7iu!mtQ`K|F7;aT#pN2X>g$UzWLqgZ+Xo2mrCehxaXIT$g<2E17U`F)Zv%ClB>^ ztA7teln!F%M0)2-s3|~`VNR>Au7|SxSXr!v* zj#IJflG#sXlCAyMch12X#f9lVL z;u9aHk?ad&P~ia z*u)k(T{<9auI&~f*p|sc+fk>lZxYHhX?%eA<*3Wmq)Fg)7ubc^RjAu%_fr zuK#KuvEzy%f^ceTs@QXWFbr+qeMn0rByn|L^PN{Z#k+|BR}f089%19_hl1;WKvUfHiWkex+MYLpv21!c%U!Ujv{?~P` zbDf^2!*{$t@B6-A_iF&-!9-Ibw1PB3mN{S7;g~B8k29DTSn_{Xd*5H|I!k?dx7HvGg@}d`T{Vo!(C_-EUGT=3j`SPYl%kCU zD|pPM=27@krGH{+A@^VH(#QlEJ@^wb2en$^D4YW71$-TBl+6D8R|keXI)7@#@8PQ| zE93TzgH#RtLfB~;o#5**9IAPEIjB~gC*{7~<*+QtWrk3S*QeiYso3l4)7jh5jHobm z9}2qdN@u4NK4LkTVA^xscy_W_vPB~t7V?}798wJzZZMo1u{7x#a}f_!iZzl`hlCDV zt+OXjoZ*Q>$p3F~7<0hF4y`Ns!r!dSf$n~8k z+i%B~>qyT|PYEDVX;7kn=@u3$ap5`-_A-Ag?933-|ieq4~ zhm+Ih=1p^l>0e(b3F}JGaxht30}MRC3o!IYcl$r-8`i@oe(ddV2)CzLX@Bb9 zW>=}=W|Ty=kSr>guEzgcQBL~X{Sp&(iSa^nxh~dQ21kEtvwH1QwHJTgEqVoHnl!i` zU`D-|b->p?E#Qg1))kHX!p-~G_!G_8j%aR;l^Id zG6_7O&^7HY4X}DgotB%|{$uq9+BIA>Of?&D32JZhWzBA|6HKv=dr z@s=cw*`eL1cV!KA4C_;N3J9<6?~=jT64Dk6Upo-DPwl#jy*uHRUEXSTX{VTmgI(%Y z^v$0Kh?qjKh}JvK-fY3ghQ|@CZK!pA6Q*)75yF-SOKxmsQ4#Qzhqo2?eY3VbQd6a# zYX9R~gPF)=fmcv$mkHVTx0g;ga=d@=Y2dEGxvM7^@4RNps1w6q_?Td;rFjxuOl)5_ zb^xw!?vA# z>M`Y&lcG&4%3g&fzs!SNVs2iB>k=@7H`UI&(S@Qng5lqtQ6n%t(1+^_@})45zy^k# z8hiTx(?bJg!mq$K87oC&6WS@SmL~;jq`&}Kvr?|Nu&9*zmvP))Ltec%h9vA{d&EpwL)R^&*zFgyv8c0CFM&a zCcnb@$do-!WXG=y>-OUn-5GZsgB=a`Y>%*iz1O6fiMNC_#Bf`5n-m|vDX+S($&qmV z7nCNmdWNi~ySLtzDD>}(rBsXkALUj(=O#h99o<9poZ!`)!wYWCG3-dmE_uzR=1(?2FR+bv?7mRBcZAmVhuN`e z{QS8c)B2|}+|@O%-im@3=`#Fa5I8b?`&D!T7Zh`tGYNttRJSO+)7Rhs(l@aEFGq_8zaJ|5t7wh&TiBMZwAT+(MD~h*RSCTU@VAdHTA^UO;}4 z+s1DkYx@t}4zOHIttX^w;8#`WNl=HWZszb1ki;e9AY_TDV zaL1^e=J(4u&1Yth)mI00CA=G^NENum5HAPocOpIpq(za=GL&YR=VG%%4W?T>C5{U!pwFh7wihzpD3bgcgzr1Nh4Dw%B2@l$x{?X+Zv!&!@x zssq!eoqRN7E-Oj;bbl=+H3n#pCE1=oHGH3Mj4VT`=YDQXPd37!_Ti@G{p5ypE*WK% zDez5zdJ4Vn#mA^?V)`~Y?f(9UJ;i(M{Ax$fl^tVO-pQe?`M{?qLOff@(=;}y(KzF2 zehIy|;V!e?M>TX7?JhhW6WYjpG_e+Z=-IOa{x+boVq6XEKv>({B_oToSIA%J8$>ot zezhOD{l2Ya!jPN0>t5HqO6cn9c24;X0pcO5uV+uvkhXb{N*C9CC_n73#nr*|y{E34 zEQj0dwRZ|+pXYFljp4lz;N^ARHLv_BS8#V!q1v&B@-9*be|S$AmGv+&oT1M%{wsck ztp3e7J(Xl*DDkx+r2{U4xeX1epl89tSP6GCW<fr&8c&ChU&Ol-yRZt$#s|4- zT`BR)5A9P}*fZ{j`vqK!YCd6nRh^<&nAvuARZ=gYG{$LV(|0 zun!>^Sl-QhazV&@sco@eUDN;SkG_AW^&x)-{0RE}3G7m-XB|#>9SF?)`~nw?lzOFn zeU7=D*A5fy(`olQ-o4tH9xJwJtd+`!wa&`AxNitMWmKyFdAEGT6-W?VB_)I2&mPE| z3#A~0I!B&k1$-8&Z1q9PpsKGX2xO9N+p?Nr7zXP8kKn$8SaV*?`6`8!@bc(8ho2uP5HlL zkq${kat%QklcTJhd$?!rjxPM$HO1C;p+51-z=Mq?ujAO5KpL*$y=By(rB}cU2mz20 zBP~UY&GDP5Nj5w^nm2a-y%+i2lPzz?#$q_o)1c~{t{xm;ZEsjJX;ng8dq4TXqgr$u zKXe~@CD~e$STAY5vJr=yC$AdTgG8rJTsZ`A1bqsG1fa7MTpMpW%tAkkEdGVHt2~s! zEl#jA@T9^#WQ7O{w@*LudTaUl2AzAI5R_{)&)?Vb&mDSaeB+(a%M#Yw>m6SvzW9aR z+Pq4kG2)RcKnsg|{J*Uj>!9X^UEp@_Z;v&l}eCUX}0|V>sBrFj?0g*!Xfm*1!2?rY+%<1V) z7yQWjkyZDv(^^`6gn@On zxQXt;6n(QlX3cR03YYbHM?|E&%?f1QL|?xDr)R#6H>vBYf^K{c;Ilu@gdxD*INpMR zdC#xL;TMEiwbWykFx28WRSBA|9>ik#RxFxO823PU=^*%fP~`E%BLBm#ilbFQdnHZt zg^LsicxPsIv$3&RJ2?RirO36<-NVJjlNQ0jEP-;@HoaFZ7ODyGZeuKWl))fe%H@s! z`)_$@7Qsvfj{&zkfVTRE>vIbYiuU#g;G1$C{}_4j$m??cxn?m%xZ&HU-B@-@N%?X} zm^g8bkuRrM;yRW@q^_~=a625cYLfAw)_1FV<(BK^vQib9-Pfu79v-A~{xuHxA10r; zj6k^feRga9WQJo3qdiriA_h&g<5;(Y=z(Q6mICW5vzU|#JPnt_qSxf=2FB|ALUm{7 z!vOm-Bcy=Yz$T-^M*Xvyaa{AatHw(!B>jgck-+$PP6GMc-^C=Ko>W-qwCF_z8#Hj;Fpc3yw^&w!h=Fw=0+`!2h}c!$dBsw^ z>df#qK==g?|`xC*m;2* zmJcM7@B3}1^Isd7XEA=xmq~yrfE<_T{sYI>@s7Y7$0Axh<7AoLn)Ch;lbaV<_|6>T z{Fo8UWsQU$xMvW_FQ6*T-8d{#)Zv~HkfUSnIO3D}hQ-vx`C>1~RdWK>EyD>L(P3jb zr#?Q>&!&k>Oz4r1cKy)1kRcHEJFfeS$uoG-h$NlXWkw^ds4{;-&b5eYVAs6opPwai z_gpNdgP_v5`NgZ@IV{6M3|@?(fcK|4lH37Q1%g9Rdy8Dhj7a~qyRNBe_{#-F1A_|V zgs=f_$sSshiAagWk*SK~q3zc6+atjuC_Fb4tHhsot*9XP?S0ym`UfYpa`dpS{x4~! z@ta>X3}4+asgnhephbb&qP@MHAd0>G0;{Du-p!5P=e?W%8nE;D_q!5^V6-Jo$jYHn6TlB207B>cy`~??YQ3X?z&0kZ(eU6SF3y6*KB7pIVAcv z^yc1uGmS14*;w+x7KAuqY1hBXfR%R$IuSUH;VkMK&0r7XvaQWPU6$i}M z9mxgk2^-x0eAj2AP;)e$20RKRVvrBjnPIBKDF5Y zV_SyH6NX5HSuGG7>^Wez!;4J&JMBf_i=Qz_0z!jHY@+}C@r4|; zLI~E8fEW?ok%ng;^8osNroET=ix6+5A;F|v(~(Fq$&~LTGRc(asF$N-w0%8FvZLZP ztH_40qqd;SRPECT^#frSkN7cnJ+<@IRTn7i)H|jLKY8?%($WWiI=6WpFifu+er$2` zsM+sIFpS^t`+!V$q~vZxb_O(Q=p{2bpT-U;RwOH=l<)7F4Sm}{g>*;4RFDu;xJcn~ zb!#}`oY+vTJy%ruy=`$|Y2RRl$8U<=ldt)sAxD7&lEN#K?jz5oq<74Go4EMMrrYW* zd>(G)I+`px!!_VZt|MY`{t3H|jilR?!w(8545(YU<6fL{vAxfH`k-aySovF9b&bYj z55+(8KB(ArPc_FqB2w$<5y^r)X=ipBWo2D=A9dqlQ{(PB-iPY2pHM=2NnD2xGK~PZ z5ssa}P0*VV(X6=e6vWs*KfLzN3MOPDBT`r~xXH47`O+zHsK22He}dF<%Hm(qR?yz# zHHbKSQJ%V2sk&Oy^V*vGRJ)e0Ihy?S*$c~05=d^8v=#qeFg;<9ksN&x!DJ&qKHPFK zsxPj*`RD6ZVSHRdORC+>lJKs_!V!x};5S%IiX_ota{p&0ux z69V)`6jL^q-}u>3{@U0i14#f*1%3zaL=;0pFqxA3PRf5>ki0i#>GuqIaiJjbt9eGd zV(muF;q!|9KTrVJ=t8y`w(O4ny+Y{d$&)*paD?&rp%9>xhuT|G>X`3bm1Crit}ba4 zrb&EgfpdZ`05S3VF*v^STf2aEm@tl;7Moms*?y4zf|Yr2=C%C!;$X8fL-j5N-FM`A z7x;=LcjPMdCQw+YiMQMJ`N|(+{OF*}e>(FHZx=gP{--Do$#sN#mpA~{@89p;ETy|!+{cvhDChm0PMpv*{4*oiSi3(3=)a-2 zF|h#aJUTDUH;kCOuodX*yC<;k@x%wRw))Irsc4EEg~$f4+D#t&r_dpa-$%J+dD2x{ zB~yEo^{|6@x-;4Ab<%q_#v%!}b&wAHTV9}zLV4W%P*@{*O;4L=_JjDh>$5v;pi6F=wvP^RK6ZB+Tlp~=ZH`CQ+?wRQquL�Uqb?K%dL z4#za5l7_ofGGE&VT%dTRHY&--M1#8*8C%S21wvh!UES;_s#pa&qfH~h9^_?$>m|%z zu}e7B17-`s-C&~Om=-Q*+NVm^>TvF)bP7Msd;X3POI?HR5QQTiJX#+djzv1N(|LIO z-u7SRX_gyzk%CPF`Yc@kw0p`*EYFq6X_PS13m*-vBFQ$ry6@JQhk;-M({@^C0|wXO z2N$2cYot_T2%aKU)@40ExNqzkL-;AF)Fnh`-QrP;_2cum8IDgr_!d@<9X7A*DhZZ? zrz}O84l_ln);GcMwoibN*fSn`Npx$A5H{gyl;V&H~%R8o>c;qv9uD_&`c1%{f_+FjZ>>xbJUH`L>+EwoKH-lKt!S@Jrp zuws1hYlGjjglDxCDgg@qL{Jz8QyeICn=Lj+le&=V3c)dqv@_0wuLW@j{sEFIh zWA1eitag3EwTd8+Htc?g@dg`3Ldf>%U6tdmeSSZ8;)X-9!9l@~%nZB)Ltc<&2C#OL z-63lBBqTH6cXzR|dfbY&dB6E(aivUky8(Ir>%26Hsw6x+_uZZrP2iz_#39cUqnX=R z#rc;@wyFN=LWojJwqC~#hUB2efe1q(<^HV;W@edi2MtEvAgoRpg4?RQ_bmM~oc(J( z`nN?!i7&PLd*A85MD+s?3QT5{)H^bHLS2BN`4946sWK-d;C|!DzX;`%KcrW$$ z;j=2{kK&~|fBoIT`GLqZ0nrH?b$kc#`vpb~^c&`#A6ldF+EhbA(xz9eGwcV{ZKVz$ z>%1(Y82ikmNmZ8_tZOt!aS_{050g*2FH)8t6yBy~`00SfYMt|MYZix-fF*7f6@Ga! z%0y%m?(cGcHSZ~3#dOp`IL3&g7K;m%In1x%MVQ|;L{i|q=f&Cv5)R-5XoOT=f~tLh zQeYt2H2L5&=7T%W!ZI+%g^8hIo5496(K|lt(dIK8?|)N*V|1t0m(CSX+|p7BtQ4Yx zxyBWJd>D1^@lphDW99>1#<;7Zu<+PJhTF|dH=dmeSnYfz`&`XKcJI)Lp~vDI#A$ zZ@Aaadh^|L5FtY|g9%a$)~s8<_ibe;-+0P)g9-`N9;SC>3*Cl170Oq% z$v8IPRDxU^gNlWV5RdDVNmmdG&|}~j(e}@~|G8yrwXxgSq%yJps%88Eu2Ex(!Pn)O z66XSNj*;RO_T5WdF{<0{qNmNB2S+~ER##(P?IydI&_|({s4#APa8W)FtpPX@&;$~| zA8-V3Ic==00NR3{yRu-hm4e%tXv5yDt=|CrbOk;PzSpl~o%!K+`B|axZFg&8S$KHq zr(-1Nl}Pv()+;wpJsUE7^hCI!PbX0 zT=&8SEX#H!kQpb!&-l!+1OhFt$UJOmuh)qeW_hTwi=OA*IRnY5E#HH0UoQ&T=H%R1 zc>8_^9V?z@QeS%DdS?dpp>8NBhS(RHTB?0F?!g}A%Es>>EJwx8Ki>+^Qca}Fx?uof z@F5ePnD~g*H!oCjnmU2PK3LbX9D-lG^m@M#1eZX2}cp zFV1+41`U(M@~UYg_W--1P4ZVamYQOkxgKH(`W~%@3*Rq?YVpYXZg#mAsoVO8oaZ8L zqrf1GTmUo3>+asn&+eb~6LP-u#I&(BT>DD+$=h!Q{DUK0IT{Heu8T;#4&EX6npnP| znFSYO@75QKe}@svhK~2)&=C2dLq9&1y%pkjTn`m^*mF;n7k3%>;wZBb4EyOQp2Z#& z3_4D)HHgG!2Z#LWlG>XM{MYsApCn!jP)$E9U{pj=>uvq?+>a{cT43RUVFrM+l1%H* z?>GQ($`ILh#$xyO0jHPtm19atpoQ&t|7WDud*;49#*~39j);g-%sg0grFOd`1hVIW zOe^8AkBm!vWxGj=pZ}*W1Fnnh;A-B5duvSG(+z#gO#*Qp z$POCA%?fWT2MKkMq7&2!Vm#0o#+2YzD@;+D3?t1=7oi8S8&cBNA!XpW;W4hIdT^h=mT| zUYI(yc&x+m-Ctj)*wIK0&hNNzIBvJu!dk5h&%Whc<+jIfW}Lt1tH{N?;8%m|buj!u zRXvZ4FL`0Sg#t1l;AUn&o0M_O*DGIS98-E~^3@p(I(~H9rx9ys)TEnRf8Wzhp(ijU zd9+$LW>-L&yr?&F??nEc)}7tyxsHz!$LDH;syGIVH82WO!NKYNXQ28ydn$k3EH| zRB8!Qu*-pR{UT;Q#Dc6qx^{fxu1Adz4}@`8h2W9{c-O{jQz4E&{ajt`pPcNTo1-3c zp=5bw>+!m~$78N9>*>ZB(G|qimOBpe0|AB0#S8G zAI4VrnhU^66uTEpcU;j_>AeTVf1CSEv!K~~zqPprLKlL%(Xd_dwJ=7>sm`l!$A+4Sk-7MjvC03-&1UV%>Z@83T{$O#Kr zR0p`f#w#Mf0FkMv@aVSP>L$=m!TA5hw-m*4jBEH4v>@0lSY!EwqJ`=V^*I<2E6DyD z7#~+ZcP`HI1V%f&c%oFv%frw)wal(h!$AhlE~zfNNK`8CbO249Sgc?&dMUAVJ-?b6(e}gVc#w+YY7J zj~V+XxJoy#tJJE?#$m3+$L@q*4DbyaV?^m>=%^-JvToy58)zGmrA~sX0a+zjR^K}V z2pyDZdcyRUA-Jb~fwGKNK0UpsM+Dgmb`iVY(xy7m{?xNuOP9I!)YvEn9Wp|>dbk{LRGY@+;_<@W#XU(z{Q(a{z4~8?5!2O!Jq|-&#FS*vc21)<}$$O1*=VweWH!7olR;{!sd427qP1*eqeV#$6R<~sqFci)r z@tH7F6n*-g3?r@I#nrE}@vxSM36HWmkFuHsPmz($dS~I!`w8!OJ~l@G-XwX~MZ&0HC!?Ot zHv74tSQA9G7uVtN-SGT+bY?~dDa_Q@Z*VOvEZD{kbx$fofG2QXiy3ffMpG1dg4w4c6e#UzEdbUAvcJgg*r** zVp7v~Nzn;anr0QvAk703VLSJ<^%Q+Fip%$+VPcGI=MLlf+PEf9NC`n%H9yOjswco~ zDV5qkGD4ZuMG-t0dU*6PYj2#(6Lt2C;bBSkx>Ii|6}WX+Gfr_X(fr*NuH59t&UxHR z6gX74jW~@WBj(inr1)k_|Ir0u*~FyI+0QroA@MuLIrrtuDQIC)nYT5XTSSBw3Y;@o zwpSKw5g1{nO#eGE3tm{WwS=a4C?a<>`Oi`Ic+_$7s@>+M_B{Id!Qky?%Ysuo^9S}_ zlC-is{9$&AT%|(j08{7&tSmNjdDZerc`sM1@^&q2%BOGX;#t|=D%Q;&nQNM8dsnxH zW`z5cYs?9`s< zJYIWo?W??mq;Y@Whex*+B|kscrL3bmGL3_+9!XQUh=M+c!kwCqj;;E*4TKA|;5R z5PrAV?7G!V47CZRHz@F6e|VDluzR%TTD7Qrn?X)J?41;B{Y$eW3Yh->ftc4LW5ES*uRgjnf{ z4G%-%2{i-6ttu2tZSCQlXrdVb!gSkdj8Ibq?e0}MezW{^iQJdlRv{wZ+m5NlK2@YX zbZ4AHx`k9+}cjhoaYxw9F7SCfy6#(somMhi8y}faS#yVIJ1xR4IbCV#(&3<$O^};g4(2E zr=0OqE%Y^2RhBk3*+mGf2fBjxiwqKso7}q~No~O~Ler){oS`zP*oz zBDs@6@RH*4y7fhd-W6v3!{7e7NQEQfb>sKTlkF`nr;J%=glnfS&zE1jda;W{;TY#; zy7>Lq>0}}Ao2#u5Jo2whN5Gpx(VN=8M)R`XuQzYMSRekyUr~Gl2;s?eqbn#-?5$!d zii}a`&3SVajiwbpu>hn38Bq-0oNf0zIgYYN>RskkWc&^a^2hi88g3En^X%9|5HaE` z;-zoLA&Cm!Cx08*C8N|^%E@9m;p*$>b4!Yx6dasC^b^PFLG^sx4}hWWVRH z;W@sH9uxAyPfNA$Rd5i`KU-!YE*I8t3V0`aJ!!Kpk4@u=#Fcg1icRjq4}4wSH}{xr z65_Tk9Ll}g;hk9B154K_R^rl<7ggg;+`&bH>{nwr)%iV84y2| zojIebtD9B7N1$4AKxHXJe}r1WdhF9`)!QZS4*}=iG+Yx!xuvMG`Ek%9Q{WUMxvZDX zo>xbOJoUI<{=WJ%Z0h&009{~|vLYo3O{RdQj}JwK5FB{Xoa|J|+KC#1|0deen-|$I zg?>boBW_MWR>`Rk+i<^NIflYdQeqg66NZCVg|q7ENtm$`EKk@D%=7P0P>0txDO_n| zbdqPP19TIGioR*+x!8@L6_xfvtW)!*=QBMAh+2F{mzZH;R(mLp@d)dq^)=}1Bk9ZA@W zz1{`2SXTL%57du(#(K+z7IYpjCYYZ|pnB;Bi9NPnwq$zKk%_8&+~3KBo7H0PTsanj zI7PX?i127NC#xXA12G~DlkQNkU%sN__9sVPV20@D_Zz2xFT-n#;Hk&&FVK)>*HMDOehv`&hpqq`@UuPWDWfFu5>wstp& z_#z*04#2neUMQ)>{+Ilrb}$h&`tK&(FL04Je_OM<>B@i$pOHL(Hj>79eZ=%~|Kk?; zV zl{m8y3fYEHbL%CNs~w^zp(U}ot8CgH9q`8ZSjEZHMXh&llRrpJd^BY%$bFE^>C=); z?b`y5Cx%6BFy?fivXNj9YO_}4k5iOjS4R38B1=B}@W$>tNQuYTdOU1R0SdmKz9(R> zLRi2P7ZT7DqYI|3c!=SZ8;ni40wV=u=>ahg#iy2R`hul46i1ug+T>a=0~wVVvPG(V z+09B#{;1!=up@dyyDQh(YB;{Xc*jA;V?3=~2+Y6ch z*0&2KlO4-?QmK9hS^X2eZf2FT3bFH7pBwxNu}Z#y&SCu^D<`SyZrY%$54G2B*lw@T zyPQpVFMijx>5S2NBJ~FtEVjT|=_KGy21mo>-5I+bFhsp(CBYuHshLx8$u?V^o6-O6Qu~2ux!VwR z5RX0V$#6~?m33FIx>E5L%%@>s0_;VU?C)~XtE*RGdM9o->qT-}KK%^#6Zk9%O3s8w z?};*#5{PKc_GtWa3(RU*mA$il9Dx|P1q#0H?p+aMkHqK-<@1|IopU=o|<-U$$VN(&g2(u{RlALw^r*MW0R# z*M6!L@*bAwitrh0{{8zHu2`s+(2g7tjf&sf@z>gz72;z3(NAlC9XEMGt$hA2)e;XQ z$Yo8gwdbTSfpu>2be-QjEsxBF$w1=7iOAt;+v2}BzW*JK>7HqFOK~STl+^vpwuxG2 z=2l15kV-@G8+WOY{a2+aS!`wb;*@Az+eWQqSWSe_9xsZY3D34sqE`w{%x`iRV-aUl z)qEtp&P49R#571EOyzmp==GnKcn7T(LMjz-cx7i3b;IE6xf>TgI&ay|&+#%yW;*{Nbsq9Q+f&Ld;cn+l3L%8K5X>jKYg|KaJU`z z%r{$RJajW8p+TiuIi;ZCsLu6EiMAhqNLbpog)fYrv6NuXr>+#BPJ$H^y1l4h9=wZB9x}|@>fAA9;m7IuZ z93vIEoCG@Ol&LFMQo-zi);P`UDZ*B6->2q5AyP%=%^t_lLFD0FILN8I6&4g7j z%wlbEEN~kY19wsvEJSY4`rsBOMkmO1nJ(cj;)!|GGsqrEdGq`JKa<#`yTaEmh#iL=2)Lymh|^@oRml{nfCmwXL~B1d?v;A z(UcTPtWXy&HUF1W8JRa>Esu{5tR1IMAYnZkcDmQQ8<${{8z&lD?5F^ztN+mPA9f1l zRRf)rm=j^7-Py^6Xxlrg$23p7c1agS2)??f`>yS7#R8o}wVdJkq-HUpe;Y}OiQhN> zervTZZ?dbjvbH88G^ph@HDq~%)rX3*W^Vfx{mE)z95-2$+!gv_$MX8dYP6$CIDy4E zOQeWi;j}l%dQDC8oCS9&+kSX#nhG$tpDf2%mAe0vOPau#^u;Kr_wgK~NwYpeqN0Je zl0E{X0OUcg-=Tw_4{neb*OG$A{5$ft&xa#2IId$-) zPoUT5SK8s>SZ4RQk)mV*%U!36dD`VHjp2;tf# zVx>*e(3WQH4FJzJLwJZ}j^Si_@9zD6LC0OEbFJgFbQ09C=f!r5&~V|Jx2haNtt_jl zQCa1)SySy)#2y-RiCyJ=Uk2Eo;@yD_yA85+uRPeuKx6)Nb;NY;+qXP!XFT_Im3z<* z6J|j)Xk$U;z=d)uBmY*pNeLE3PhhWBHJ(XL_-rG8TZJYhX^{^;T^%Px&tIE|9o?ET`lpR)7tqZ z!i2oqgZol8t~-3@d*!k%%#CkasCKf+`s}Vi=~4~Lb?drlTVsc6PV4exC?qHkjlB?k z(CIQel9Z~nX3U*_af(^l#Lm>*Tm>N@pv&MRn48@jsRB1#Mrv|w4#H1ekG%Wkc#&jM z&L#VVf?VH%up2k!dM~=Uk>2JWP?*G(3;@LnCOZg}MAYr!LDoxG2hG0vUr3v-VevV& z`lS9kpY&ZT#By$x;@Vt4BJyviS}Z@g;&1UiWVEenCj09RzGdOx#CF@Ay_MMhJH z-x_k8`+q5IXfT8eemklELnSHkp_4>ktr&bb7(mU+~YwV;YB>En`IhEm$F_2(u zgx!Nk+M({>!ISGWn6mrdyiq+)?vqBi6=CQD#v0)~`dBwzQrz`WQ_OHD&+FWrU3y=2 z85Q)6H2t_)nu2d1{*#g|WW0USI59rGRg8W6&&pNb@SX)3F;%KY?+LLe%BK`GQm-Nk zj6PqKGB@>+FfsCu5P!E#rzu#?j5LwegzMUydj$ zln6cWmA0=FXfU~~AMRC3u33GXCZXw3d4FViInBhABf)>aHl%+EQ>~>M%ZPg!_l-i) zUmy%jXZ+{td}nuOctSuW?iIp+ALC2}Xr)aqQs-2{lUv$QT9&;UCY>_{5GcQZCMclU z^3kPn%#;M2c%kodwZ89h%Q@FS3HOSdGsEjC2vnA^mh$q$JFVhO?647o#^>5QA1atB zwiTSq!#TvjjZ-=@Itr;XY2F|W1{fGp;l9Rt0Q3;z;iU{D1;&CN7UK}2{}Qhc87WmW zjo)2TD(7To2rjqpHD8>l+lAMGztGjyRdwn3Lv38#{rtC;cmjZ!ny5TTPY-Uh4nVpS z#B)t6a;r@~Ym?XdVXO}1uJd?R-`_3by95RRc#WmQ+teb=5*$7h7GP2$Zl#u$zYx195|3Ix!qa#o}?^(Ya zRI4vni-t|*p1!+kQ|U-(iJWiD9=8Bqe@)F>pg>Hrx=BOQIUA{1rH4)%T&qgpxNss_ z=R&f*#1~i<-0?PRZ&KK&q^ppj^OI%25G|?79T}b+vhX%C5~L66UrjP(_*5b^*Ev9a zXx@zz*{0~RwRSy3H*#fufDiti84V2_5LqQ26&(sPkcFrki}*K@ElCvWDZrz zEY9|lZtgc+HMw@`bl!~0=q9!;d2J(s-(Pt}1zB7Nxms+QeJ>ZpC5#yHz&tnDJd;o^R;{3$p|kk-I;?)n zV4?-8Aj&V4)QGJ)XORiA!~w++%Nk5@hD9uLy)f;-*~CxZpW2OeK!B{lth)?RzVT*o zc!x?%7|G#7IR!Bc64~|v$k7#GzSldOF}eWuRC!g^9Z){!Jbl0Xkpt1((a&&o#lYbd zvxj2I-vBF;C@XTN_^{Vf>Ek}KC zh4#rPWuBO9(%Bb*j&Pt*DRwDYG4hKlp3reMv_AK4Uu~voz4Gl(H-N`~uPytPrx8jO zeW=Lk#gV^;%{yDg{$S%}adP_y>Y!6r5mQg((`K)!wf+7h9Kf4si%#?|4#%xOXSZlJ zf1cf9Vc?peYc$`XCaAAy2WSJ(rfCeY`DvS)-I61Q$e!&6x z(evl~f=&g9m`HmtW=Ol0O0q`+6ZKvlK41RyDY7aJ?e;uscioWk82zer|LoY288qdC z^Vpc|597gg_XD9|Qy`eMLpk>Yez=ctJ`Nu~98bZH^2w{ls7(9`ed96j@7z@;!qA-% zndwj7J@Y$`ttk$JfEg1{k<<;q|k}# zeUzl(aCLDJ+9S&95Dsi8mox_x52(J7AOvaWod#9_9yd2N8T5jVYlG+$iOk1V-28{h z6K!{fDiQl8Vx*nzO-D=%J-OmU*_8?F`+-(E=N}1Y$@y13-8lEml8I97(w~dQHJV8; z4E&2K{s!4HGMo{}uQ4eR$UbLzI*yS-xP8Rkp{Bw?%){WDhSsVzlkv}E0p}@ORVz)t zYxXCvflu-hR1Ca7d`yr%ME>&uvL%L{vd51QSMeBC?)#d^+~YF2w9`AzCnHg%Qq!W- z#cb${OjtoI$twff>d5e%;bpYis=Q42_;5V2PRjh)Bb~Z~hWQddJ>|CQvu~19-_+Az z6wcjr<*E=W%^93Oe~ZH-i&t&Rq~upP=gYBI$vW)$n03&q6HlA9+|Odp;o6uFj>yQ%84t!N?2 z-^4d3)l^mbO|W%C5zT1nSrEVnI6_DQp+kE9en-QkcC`v(#~{2U!+cxh@Tughy5K>s z>B5;kaI;f>~^ONHYtO&N;!Y;GT6qsPOc z&uv;~d3Y?P;UnYC%3UMfV(zJXg}Qj+4pG{-PbvTF0WW*=Pw5uBP}ip}i%oGt6wsY55`Cp47D*(J7Lx%U@Tx*fnzRcPKZGfeb}+6(-8ULLYilg2NnYCI75fpq$GFI zVe*XN)n2O9t` zXV?$!c&L5e)7(z*c-m*JuF&C&<|>W+^nx!a?}@5X|Gx2RdWG-fk@J$HE^P9hKPToI z4e~;>b?)VR)VF@T(_wQ;Dp5&f4@s+g@{j4V?zWc9sluk@Y@wwi^fodS!TWE&8`2m3 zeALBUy~Q?xi>Cxj>&)Wd#$epMap{IRo;|?sK=Z^>yN~()6u`;>ZbasiFJ1I9(PqB5 z7=7X{_@B&Zzmc|^YYxFq{-vB7e!c&2v+ml#id=&xU_8>L$d=^xs5rz>8+?riM5+3g>rKJ=LKuG2O| zo$Rp@-n;W$Ti?(Che2S`r!~qzuFU+lH*bXKDR&BW0d}^+{D>RTvvwafIne;&8o<&Z zeV`QtnDra1?2%q^hBmo&d(_q&xv4|q^?FM!o=1UnLQP~j5yK6}&F^w&+s5cyn{33b ze0=J@KK2LT{Wx51#JU{UXnMOUU^4^D>|b22(tkeL`42o48!e`~2YeI9h=5j!6~OAy zx&Pwm#zO8~Hz_eRxeJ+03t;8{W)=uxtC)A=nnGhBsCvoCDSJ8%4Y*mII|Vo;RT>pf zypJ+JjSW4XE(#b3)NRg_H?fRfR6wAxaCQBpE4sSmZaZ*fK(B?CvGW}mZMs^FZp%G3 z;`ow=`k%mE(krIUOa$XWlXbZz`qD8MR+AD|P*@57i*Cik%(R5~4WQWBo6EaQa#z-G zB&Vdb5a6C@yj?*jMeS4J8_o);Lf<9FzUj@|Ox7|4HiukXdq;=;xp5-Szfq_0=OU8< z=MzbKgZf_2<2RZiQCE6M-Ox(fW2t<@kA__)Qj^Olnx(8ehqRPb(jcCNr8sk6&JOXn zcWfs;sHG>jHFn?5SQsTC0rwV8bX4Suj{?f^ll%H38 zXv5>eH~C!laYe?@;!{NaFh9(h|i>H@qDz*;l1K zb8-pBF_C#$l?|vCJ$(DiGZ~{C>I-cnGn3IpIq9~>&ISMc{?r=CF_C{P>I`pjqmP`a zADiDrf`#VaboMLy*3lxNnZM&zvfR3|55}4cF`&nXvidhDQqkX`%7f!`zB^?S`-Qy^-IJq;l|8e9W+?mRQaMuyW z5+6Rb(IuzUla?gr9j}Lv02DRH9zGU7KVKr!SN${@<`qyu^LxFnkU~*W!jfVXumxqThcsCmd%L}MlP&!jD%Q0j2dKuzKm8$*Wa*f@M&f2 z46$gy>&g_+Q$ao_9e^gjXz>H|l&Aaif9!q^+PSDE|1NCLo5bjG!S;`hg%X0EJ_m`p zr6py@*z68C4zoVrm=<+|$wP6m&_y4|y4SY~m@LKUvj$%2$~iDz~6TM zc8QA=)$^17*T0>JnoYaTfFss|WpNo`dt%3cdW-cV3*X*4+2IRXRc1#l%3O}Tl8Nh4 z=yQq@W@cnidDOAqT*2<0#Y7u>$2G~TRo=f$+MSG^CuAksYUsCEF2xRB!)>*Lq=~l3 zybec~i)}#PjRt%Z#BD+#u||nO=B2@)T?`HJ`pL~dc)CZ$Fd@i*y2N>^Z~6JTi?Ioh zjEaV>Vdx6ff zuF#bC8TZ|Q7I(Z5ifG1OdmBrvzmP|uclsn#km766Vg6%~3gbD& zZvOxy^-#aagbd}p;jLRm$4~P-*~iBAC`FW~XXY3K*2vydk<#CZjx>OZO97Nw2xqqM zeVCfsik0W^3hqRBRr*goi9OiEj9PUyu?Mw2__T!Lv*c+$-GHOUS3=f?urQKzMu0P3 z^HAtpNHQ(>LHu~Ttac0*^#t&Fwanbq^zeNOaV(rZ_;7(xOf_}5|gFR*vB&QePnIt0q_cOA7F2=ibvttN~4wy{ZqLvDWK zhq4@&)3|_vXT~?e5E58y0IwP#GLo0&0=su5rT%$UJtJEuFl?v8?2tEjNJzM6|A!ST zNydPfZJs7H>}Z#;|BI z0b@D8TI{!4U6U!F%`TxX-*{Ai|12~D(dknE?Rz@h%ntUhTu)fk<%z+r`}&nHLvG)n z)-dN}82%cUy{_N$S?ubb>}A)gFU!Vtb5UcTTBwKh9>{Jt)2>bFR!Q#mjfm<|WcDGL zL|$HKP4>x&Dr6lJm(9>2hbXMABQCFRbd(Ba3=-^U%b^a_Y`E`gA8;`4J$g4R797|F z`^k6i|AoO@Ojb4w%NAlijr&M~^^Q>4XW7`cDDQEURXAld&#oBcNbk~7Qa=Wd-511u z69hwmJ(%bFUxgkoUm1^JsZTI#H1(sW`B!C9QZ?j_+i8QaxgjoV`*c56K-nr{Y)a4# zBbn;eD{43tNrpZJhz*F8CbeWvPfl7o*i3{fyzNxn+dX#!dS?$i$MHvipTNvpT~*aL z%c{H+MG?Agklo*&KetS7N(V~$<3yQM?g2&LUP%)(!OfA@XVEN7!O_=KdXCV-E zx-y|I;DO+oHJ#j?IysQIh3Wz=Bi>!Y)s}niCVV7PZVh={&aAD+-uro2$6E65n# z&KRnKQ65~nD^PpNt$&Wgfym&oZ21HH9v{FHGZE_B{y0_Hg9U}_kzSpG)<>moik@RF ze&vwxE>B2N@YSnaCK4MZaiQWI}{5@i_my!lHLRkiiVWAk{PtEEOV!9cQ6Rkd7{FskAyJ2}dB zw?D@1vQ+Ai{xiGFJ?u})%9-eP}1h7X)JY@rurN%8nz5m51XIGxsD9 zpZY<0T!#OTr!xV^a^J%KYfObCNkS53jARO#GAo(KlsR*hGDN0OW~Av)gUG@ALfsYu)R2-^))f7AFjjNwcm7_X+Y3KGW;~ zV?LtaQA1~ga|DVXnriP1;dk+-rAGLB_^p7~AfA-tTzOs5Qce{c?AAfBWia5y2pMzB zpH{IJ<#$|{>0}!k-FoqN!#lh0n73gx43-Ss)%@DG^8f6OUB->U2!qIk;&YYvh_EnX z^Wb8{uwCzB0ir3QlF9MGIaP=1DT(hOSt!zhP<>M&M;d!g=@zYTAj~;d3W( z2;tO?)6NG`CB{mJLOLR*=fW#X567*jmQm#?9Jw<-a6+MZKbeYc-MMxC;b4d3%q}Wv zja4D|d2Gfv{t;6t{B!OIfydHcVsOeD4eM23Z+=xOJ~N^`-nHv?-;8pS-p;W?zI&-! zONrKxEk8$Fuy>Pa+k%3kWLa!41!`-a?5^%}@P1jU)<0T7w{tp@MZ!fbY9cH2RC?vE zTa+NOu*L8uItUDH(IngqR(RT>e(J@S%Wf*)_0oG(>z~u?zRUaNVMo#8it_yzOS0?N z0~Y=z4N%j(y?F6r$Llllr(MMpAJ<|O1m*>z9I--^09imJVDM?8pK@9vyz5$^3qMD| zx`!W?fmhBg}?VtXZ1T|3_6H4yr``oYhHvh z6>^40D#7kJBAatw&v0-})qd*Xvhnt2+9B&+!&JgMyv$QHq+4}hz3tFo+1(H7?7Xg@ zOANCEzS#flJ>9HZkF%FbD*fvEq(%&krVgm<;Cmgd}oLG;p{$M3`VL6Dgz6VxGG$qkHIF&{`r7bSC30-|e zbTs->cxZ@cMX1P&1J+s`!OGBnJp5H8(umS($f^C;FVB(7?=^nt3JK?EnyqV799u-h zK9RPFbmw+t9?VY(2M{}g46gBXi{hOb8`D00dII1#vGbW&#C6hfd#IAnMlv_fdaFy9 z5M~kExM%S?jY5}wHGWhBgVKJ7xbCR}n>y8;tWT@nvh)pO^zhW0H)y=v(!XVA$7PIP zF=_>4zgHu?jSOWHMEn<3QO4(ds4y-K!fV%f4nqpusU|{>Op&b@%bsf+D4n=H+|{d{ z99i~<+w*SCn83S^&T-~#RI>kmy{>ttelMlgjP6SH;gYj*_k}5}KaWCleI3(B=dR=E zP*8P1Ka<98nw_a%I7%=pQ#?EC@?q~V3IU#YESNaU5;$17&n%j`L{OKaACQM1;{J%4 zDQ1#tT3?Hci=i^v?PDAAs2W-@&t2k zr?^3c_ulA=KNUEe?4vfC4=%5b9%GB^)uCiZgA9?A)GwvOdwzgV~F6P>he zBDa)3ZLS#v=P+LLG-YZ(taU|wFUdyaYsHf%!C};gA6}f(e}DEA-SdLv9>4lw^`}+p zr3rUNU*#wBUK1!WbTz9tVsA_lb*(c8=p6-1lB6Ze*0He@P%T)5_-sWTKQDz=xe1Ze z;z0npgPrO%O7!2TK@w~929m!TW=unO{CKJUYwKwiQ9$vyWU-`Iv~Dt1;O&CFW@+8xI$H-s zbZboUy?>8ffI5!V*cf1d>J+~Uv&wUPdf~RBw-AwxDp@1N|8~wX+l~8 zmAS}ppI{zpIo{|`D2yu=D9bTF0)c`deHa!CfC~h=il=N6Uo)C6JG++0{j>>`A}X)D z_!Z0tmYKShTxPT?9gE0$MY#)2l-^g`$e_BW!m6TsRdt#q)s#b3A_BOamo|mEtA0G7Sd;jo&egX1A)lFTck1)?VD0=Iq3fVx zEk!=2dudN@{Ecm%bkwnmbrM#V+_j*ykJE66n_X&-+#^e;3Wc|c;{3xheBb`ivhEw3 zUk$D>8^Z~?MUeRz2tm=*Q>J@kPQ9Rf;Lc{uZ(&#Q=uyGf=Z|VLPm(h%t;zyVXq*of z)>)DiUA-MD3~m-O12_Y`jUs80)2Eml(p+tLWP}N3%G)8>A5|$*B(Unikm|j;vE+%5lxjL)lxrYa+N1sTD z)lA4faXOegN9>M>VKWU+Sh$U;NQt$qW^R_AFKaTHZK^JJ%O1s(&d$1G+Hc7jON!s? z?A}HNvvF4@QizE#yte8KS*2eSie6n2xUcYn#h!n9r?saRt;%ug)w3L~KYoaqm8jcF zJ>WX0;upZlBB0YrnY_|}CPe{nPJ z1Z02F>hEt3XepTBk5Xy=JX}0P#M}Tmf;}WrDJXJ@_#wcuC<>V%<)5(jTH&*Y2TwaXvXT^EYZTNgjfHa-?& zutg>9R*j@hbf)`3>R-NqdwWbQ=#+9M;yP`$e9UEgo^eIdk*PhC#Y1cD97s995R?BZdvOHbVHJ@rq2BnoWJ0S&#>n;)EN_3m?JN6-HJ z`5ZqH9^WC3`Z2fl^=bJI+@pAL3dB|5^2T&}{!7|LrJVju1ltBTVT%WQ?%kT5MiYK8QE?X~@$;e1 zK>-6TorDE}7#z@J!VJ;?o+vb1Pc}FH-c;qvJ>3)bqCqsNQQ~&1j*dZwywR+s&2h>% z#_{U85YDKc4#g}xY+LYTmab%BJ|Qg~hW0YHBLv-q(;lUtLBZU*@4_Jb>4=y-k0?C8 zagoP!pXTrFI*tLxRZ6pqw?yY_sY-QsUo%*%S8Y4MLW?me%Nf}P&W-sUO;Jy;c_|eS zB|ml!N=`oX_J@5*38kgzZW;d0D+3NDv4emI9HrjBM^~1lFDT^eH>GDn#rRM)Zv22k(%F2D|)UKp)+$ z_`&`MYl|fV@#ujGooQ{_o%5oU^ksDFO&Z1JWzD*}OT6#G?r3s-CJ2Z<#mrzo23xL;{NrH#L zel*rN8SL>87lIOj(ugQ6uY*{Jx$h)HC~MSZD$1h8<3%ZIpSRf;Qr39uhR=-nu+UN0 zcwJQ}KE}mDo9I`(C>Dm#l?vRdY_EQ`8hM7soosZA>#gKHItK4_24s)#wX;04>R&Hn zdYnFK?q*>(OXsEKyc{ELtsV~xO?i{^!m~dbH~($!!mdV|d)fkvt4bsGVUuELD3zty zRK%eC&l?!H)G|*-6FmK5w=k^!h`I?fa{!FwbZxP=+@B6uPbh-jBAfnf2c6>NCjhbN z+>@J_G?@7k;~G?9>F>WLk#UDv2?A_7Ng8RWeGWvl_nYVAd@4oW?f0M7p5PC05L>%| zIsc;mju=~0`p&9*@ZQDpw~ti4oG7i+o~-Q9#^KYqXy%_k>zk@>E>LYq{$SB!TaMDy z_*%Blv1CfNj@FqPtLxXPMqD`9jK2$}0^0>o4<3#08;$~uY#v>j+GcN`cR-_^WIm9j zNcvFfX%OFeD{;rot)npYT;Eu_uYc{jE)z;n2Qexu3b$j?dr@tsYrj5wR8(?P2Ij%oM$v`p|<>hwK9T8WJKdPsE z)J?EIH~g4OoU%Pb+)P)be--PbTc+n%iGG6@o zAW6Aa!o+Ux^1kVUR>7ljRtze%(J|Teg>5hl?Yk(@LJBB$P3v?}cC zj=|2sXOl-O1nb)M#B!=;Y-e3gNs!{rMovcul{#mePP0)2@qSw1-T1hpF}P{1SiS?I zC7fb$y;}TB83v+ySFAkxBb5}XI~-xQr;eun(-GjeTYh6979fn32n!b7d|HqqZ3QGH zk3RvXgpef(FT~|(ZKylzQ|C8$h>CoCB!6CUU-wx|%W6wt^Vg$;TRCQe+&1`Ibk zF4w=`t&w2#^EvB9(bNrj>GZPndWtKG@Dx^>d_QAn8sk6PqFWf|ZHiwj#`-YzE1l0d z4DKU7e2{Z__aFPS=oKbx(8rqEDCBEEs$CQ-@9* zv0#M^*^ZkJRU5bl*O`p__dAF=GVWtfX_eA{*REajz`g_Joc;mpwxP4ig9@Retw(77 zL*t;S;&4;Q>DTFS%5}^A$|~?$;_bVgpW`oc_9_PZB(-{=89@bz)=Q0Spl3FA_R6C% zYL(N`d(HqF{U41ypkt|*oROa1K2&VX_lR?pOFU1#)YfFXNc=D{wx69vBz!Xp_A8@@ zN;eQn2+1ka)C12UhD887p9z#dA(UGFpNGoEWqT(Vr@CQXXoa_fZoA=Sjd9-cZo{KH zlhRo2Ze2O(U@$exyfvqa$4qbip6=IJ+a#Z$C|tPkHdEu)gc%BxM`DGyXu46c;qr-i zdMO2R{h`!I*6%m(9)-uW^pEiNpy{KY|D@N}{uX|`<6!pU5zl>LGFQQFy<@#NZ;2M1 zz+Z(1yL@5`k98#7=}nw2q_<6}s=5>9~Nyu_xi)>H1kl{le9qlT@ssehX{o{z{t<%R%y8Lg<-f}1o+OA(K zRd{FI$&n(ZXz9b+xKZ!}>y^914Z-_2=3T$PGd^oc8H8OV?SlrDWAEm6B(6Ju>T{5~ zC+o9~_%lHjg!~DFq346OfquE}@{(EZVXnSIWLZvDaS7ZlnB5cd#q4bBvuDrP7v^*x zs_t^dB9`Vojq_9>)@)o{N`C(I6UeRbEiX1|{hOlqutkIxZ)M>=@tqUbo}NSO{OYgoN}#d?j}Q~vUqO+y(&-Sbz|c_ z%WK$`*}f(JjE#%my)TWsdkf#Y9J{R<^x6RfrRFNO)_9r--6OL{#-p}nX2xZECeTV; zHN_b(tN}5AP|rY}6i#i~*~$2ZhGfU0@okO3qAWReSnFPX*+-L9$<=LszSdcH79>7? zT5qg&CX@^uGxaY?58r%=dEXYV&erchIllVJ7}fK}ae_Q_(J3PFAAEi#oA6*uDJv&$CWjc-VtLt>){Ed|s%ymMW&{s?0sBx=yKw~)d?hziJw z48kN7GCv+|q$m*(*~f*B{o#V$#O0R6|K2K4+0E`8Q~Td#-+#t-reC&)w%&t9)7;-0 zO$#I||6T{NjYxjYc?l<{eurPZ7;etb?UF*8^D)70=^C>i6A8^J2d?wYc+$Jo(aDyF zit=8n7J1ua!#-Q7>g1L;bzN<_%ewab-NJ6xr19!gBa^oEZ)>L(9>u9Y%Y3~zuGy9C9rD{mMwAy)Dm&@wspRRE?}>v| zKr?qH3^Tp$<&A3++5pyM1iOkK8~@J@AlBoX|HiRUmfgYGnHbQ; z2CUlZ_TXe6#qFm<9Qz4#O5m(iOnY1fPTwRM%j{(<8VJlHD^saRfY^vEESmUEn zdR2Sh$@US%!cvFO2W+m$t4MusLn$bl$|P0xf>~Tr@;^d2cm%PshdfbE zN3u9_!4VsdzbT!b_mCW`Tg1M6 zG@|@#F4Xd7^PP;m5hQ-dFenc&Gb&gy;AYJ7&534jC^6I1r>Lu?{NW_Ht9J<&O~rsh z1Ay*?OODWk@hKCv9LhF4Kvck1KuDYa>ajmY6tFgE{NPqZOMWEvc$J;?SQlfYV7I01 zUd9>q+fxzko+rJshn!j}->aIcss6YpD*l{#%J<;F)8~vNy=@+$*54V5Z{VseDK9_C zK8X=!@tLcI!lMP(u8Sz{mY&OgwgDWSGzGG)gg;KYUoIz zVU>E-S;4G4Jx2&qC^Fu<7-2p|fiO~L=xazp*nvt3(FWV_9O8jQk)wcnZ|J@X*Unj& zGc|W_9H=%CB#s(DwotqYt{4kb%J~OZj#Q{yvOEW;;Pq{JZO<>?f5Z6C9ZE$h)U7+_ zWdoFphkj1`Y*g?@oY@=wJiuOzbu+Znc5T@A>4p~4MYaS|PgQ!?U2_AZIsS5bDa4b0 z-Je{oN>I(#^wrkjd6qU2S`Gh;uC9tlw!Hmuh$Z@Q)q4Ky-IbnHF{3K=*+@D4i4)Hf z_%20m->*-RGGra?F8y%okAj#=0J9^VsLh1-nx80XJ^vtttwihi5)6|w*4+5;oh=j{~zVYqm_f! zS2ZX8A-q>wm%bu@q)^#xADeDim0+1oh`635&(~#NB8Y|P^$h@FV$Oia=@VvFgx$@w z@az>qgHx_)G6j6k-stpu8da=*mOF8MU5cJvn&|S;;$Wy|Tdg9q3m#QSN5FQQno?vm zG|O4(!k4e?2eQ+&n%4A8vT;F0OyY4-jY?8;0UJ%>zko?rCesYcOZC|lzWTSfjE%AX z*|9kx|0yR{u2r&W^)!yAPq}x_5!=76T-y?8eBOUIuo#nb=ZpnAo!? z*}Q0&$aqQ-{*;c`#!jjxwp{QbaRQ5yBC zz}TqR%R*WA8I&4~p00j>t9W=-DT@@_L6QIZ)}3>{TTznX6^+tJ_bZW$gX|Oad2}x@>+zy+ZE$n z@O-y#??QFf=Om5|au};%H+|DhOjI^@u*p3+Z)k47u{9*3>h9WHBI(wo$@~-Meh1oA z&&QN;tP}2U-G9EfTfZH!cp7252N-W<=j5#OyCJq6OtM1`ryUFJ4XNLv8yFzU_3V;YM>^>q0XHOvEsw#|+ya$>??8${s ztbpc;!}nAKM`WdI;4=a#DpofGUr6r~E;r0si0mL#X_$uK!X~1X6gVqZKQ)9hnh8BD z;Ly6DBnvNSVR7|TaWYuet?@fp{3BBL;m1O;Glpuqyc^o4k(tvy zF0z>~EGr236RKg5o^mKX0y>V|iG1D=*OB0Ek^4q7*$&~J{DO2$m%|3qt2F7G2iM<-Z>2YQxSk)!N5v=c7J}f>@7}#_!KW_@D5AKU< zUQR#eV^;XeqJ*;dRY*_zRsStx^43|hHo98VRTYI~H?Ymny(mLk1`cV4AdHvD#`pD! zZ{qoQlLRXi%%~!AEA@ZppU(ZG0+LTs?8DR4CFVFZX=K#TWau2lZ+dXCE`j@XnTcpV z+!`(t0uZglSeq^TTEAJe@Bi0-pJZuOZCaSh7cY-f%Wt*&{By7%@Qe^OnDHOXBB0A5 zPFP9iJz9PbETog&TwfyM5g_^|ALEx-+~U!8T^KPz+Y7$yUKeiJi87Qy^Zyi|$_g7t~NM)xgGC7*t00@xk}&BQ6$t;une!JS($}E~-_V z;?!X9#`fWRGLkguWh^&L2Cp(zG@fG$yL;*ooVQMyQb-LUVq|=LuoAAU=;Rrpv;yC% z;vP=Sx0$w4-CfsCNQqWGc-kEkKk%p!_Y=6S9336Ir^GLv`+SAe*Leb=+jpAQd5~Va z4H-~cJDs+FFC~8a(jhl|J(IkH86yES*djWjNz;uwzDXV5mYcPT-4z zxS+r=Y4O=`fi&ZTCtCAHDYkis9QY;OUQR87&<3J&oe0wcd5AOLud~M@uz4vZJwx@H z+LkM0hgY!v5mO}fTv6Pcf8Nw(v6v^D@ zHpgy@lkj*TOC3Km!F_hxk|VCF-5OFpS$7pi&M@mioky?>1C2}llS3MeP%egcc2?11 z#sfJEC==eyBK3G*!Dpq3BW}Cz86@9)QLmn$9Aa|jo>UM<(5PYCCfoz3eNblt=tBXH zeF#FwTz^?;+?vR(k==i!(u8)xodsAp=!s|8yyLXB^qi;GUe03orVk8f$3Iy& z^LidHU?MAytQLqo^4Uv}sdST9Yax&}@5Pbb+fvf*=a;b7+Y@w&vaKH&$`FdtPgcsca!(hbk-AESo9o`J`~ zhe6oB;Z3ZOjdc)21mX>-H_{i0->z2}vEB54S5_vq&ij)8{p}jgIiKs1cTP#*;)wB_ z>cIi3+?1w)IrSf}KnQ+bf>GZ0X131n2 z)5E?W=Z;A!$=z@2T3X*4Gbt?qBeqif7I$-D zhPVPEo8<22KfYxtLIZ((3x_x9UELm6alF`)S85IgDz7#yIz+tNvhVY%14~iKo1F*s zkN!k#br9a99Z+77E;9H&X1$a*0%|jgM>LtUtJda}GUiwQmif_bJ8SSsnx>haIt2X= zHDHRFSB=T0_NDFhQKtI$_E;IX9m{rnt+$eAdrY4$rR!){*oJzWBg5A4`0i;;=HVZS z-dFi9lJ1Z|H(>@0>ah>$u|J8khcF??irp{~G-Doa;nhyGVyUp?92Vwv>tcRG{p^v- z#e?;;T>L>ca_8SCvLllZ7oQrElX?znUJq7TNaPvDth z>Xlt$U}fdED03#ux%-xG$m}4`F5`a^F`2o(teEViQSD!;o5k&*XHG|d5$#w|nC^&8j*%!0~lCZ|?lsA>7 zhmqopyv@wy_op-+lq<|Yl+%ZM%spNCg#A%Lowoe1b%)50{+D>F^INh0&$wG!fDp;( z8|%)#U6Jkc?ZVf05!-L`hPCZY>79{F+v9Baf*dBQBDwp> z@s&nB(sO4$QdtQg102aS>`5l+cIr-}WOn^XsQjN0VSLa2Jg&M~ zM`(&9dBP+hN!PO#8k*G_ogoc6C}PKMCNBT2tx zd-n?qu|)mn0#FuARXTMz&(G#MhI$4~A|gFSHYS>GK) z)zjtBM(CD*6F@hv7Odr3KES0KjPIB=dVnfEaUV^HLf}p^eRvv>+v5Fya|rGl1^gHl z|Krzqmjsdku>%Bu$&|9zQ81oCgUc}jrcHFl-K7fvz z0&ph4O=oF}i#@zax@250lTB(Cr{kR;dJgZ{E7TN|w4L>MI9>R+hFv|agCl+g)u(E^ zjT2_C@E0X1r*mxIe%a*w3T_x3(hP!rD^U)#qf)^iNi#3O@3caJVC9~<)aa!WX1inJ zit(ctjE7Qh(On?%IOr{PjF!B-(>;|r{LLNDb*p`K|FwG}ZJPT_!>IR&rV66|$KOIf z4~!x_V57H*7|XG^)oo8O;H6?Pt~!1x$yitXqyb%GBIzb&#vS?CvrBi4W@-!e8`N** z?Wnw|8uI7jMp{73>-;mX-QFQe1Hm+eWB^SNMIib$WNM(X%;VbVdf#?NgHH(MENGsVeNxyr#aKLVU@5I<-3`E6PZ&JA6u?D z?DODH(i2pI1lN_*^r1)(B}08E!WwxX z2Ka{s*^D~Zv@ddR*`(Y_!JI@O6J8%8yG%OW$W9+o$-UErrBVN(+#te* zP|GOsO_wa1L41WG$N#x!>Qe5J>WIrDO1tcyb}%p)99lDKjbUWbr+D+Z(~hC}5SGYe zYlWVTM!6SzXz-0MU+lYRjX%h!?Ay+9wSgTc(7f;PLay+MNNft~g*-(zFN+k2L0S%@ zEn>@ibIiW?QU58S?2qc&6u4eyy;EPTu=eBpgg-(X&RfFej8hn$Ep_h_@o5l|Lr~dY zzIugxdfNK4W%jnO4=-D4x~3NzIPtO2$_aHZu9j~6xbU&S`x!t1l%-;%FgsJwgf@WQ zapLTi{nZCoPt4;_-+dL!XCEJ2rmtL7xl!8XP^@;MxNhT^xWd4jl(Md|oR-XR^Jf4v^0mFn3T@L3*ORT3=mC#X8 zyA-zHpOhL6dV~~cAX$lWTB+oIx%GDc^BGOFg%dH5@KaJEy4~|w<<14&kf9=7@=^;{ z8v_N!sk3BS$D|SfGwZ;>ACRVzv;UeZc|4pWxW;D zd$O{3{>jbFjiyazg13u#^Cpi`pWCofaW+cV-=@Qi{_Rlx?NfUl1UDNmZ4|#;u{9Wu z`0_;+MhG;2etWQJxjl$t3vSs3$R911BAhI=pYZv3#(d~foxa`5Oojj(OGvB8^YS-K zo@z<+3GQv~r@rP%B#Cx=oJDYxXm=HD@17B~0f8s3JwzhM;Nbot@_n^r@zUFC7Vfoc zQdW&>6ofg`7q}2QHPSYkdwhL1I!b{m(kHv*4*k1ZU_ZM0xMV!BAFDE zKs3RS{B2;D1zA+XZnk$=$F@tc^=xDQ2f$m1;LTWj!(X zDf?8YZkaN^TgUS@sVIs{|CkRC?Wz9o0+Vw`eEo%v96{p8>y=X52az21WQcS1o6$Po ziny}A*VS|t_@hs9d;fjOk2;1)ElVebNo8RlZJR^HO4v)B zh*%w_0$5D0=AndPrCROdXGL55?DlPb(H@=}JQh;A_k_a`f!T# ze_Hpr!^43t6~UQMmUXrVB7Z}XfvB8-h#J`?@I4KGD7rc*kP~m&+v9l*C?W>&xLWKy zwmv(MCL3Gz1T!(TK%ml14%v=7?J*ak8!1gOFS;@{#9v>Ow8*XTL9gTEoS3@aOYx+B zu3slKM5XA$y~V zlHh}`?$g0GJdZQ0cCXZ#748x@RS=ImopJEC_CY54Nvs!nPP_r=yVq7FvDgY`H9+y#$n1nE$jT`#__6rG8H9HShXjnIl1{dX7VWk%guZiskzFcUhr)Pg@e+&>1#!)CT z3Aa3cF(>1#K1MT6hD<@@sZSiS9Xn$?7G4~TB^I(OKm@+RqJ8LgO2hn*b@ot>R&*3M2sSL@oi zh9bDE47~PSGM%B0i|hH)b+25$K9@qztf+-E$y3VZ7LPz^c%YTZXRQzNGoGw;bVmpm z?OQC8$CHbZJH}GAO_(ayFr7B(gHLNn#c->RX)+bJ#*n9er>enWszKlP&yA1V32B>o zhSecH#E#CYAs{383n&-dtpqw_!rbRX1umqd{2GFN$#7;58SXbT-#0J3IaTNJXZ{>N zMFF$!$)WCo0Xp;2??&twvW*yvlh4M@WSWQ<`e+)f=Z|csew_PRnL^XSi%$c9W~a!zj_S zdJcl7==aOfMysA|=z~yDY^{?Rh5k?p8&wD1c5tROQ;(}$}G zovn$PS&{Ym#JQ$7%DI%Gh|)rhM=H?z)x)aI*!Bvhs3a9_1|5X@KsKUE!AnO(7JWbW zZM|-BWQanh?yR+e|K=$w0YTk~`YOuRPT7>ZQJzD!RJWE%%j_~3g`&YnfglI6Jx7O^ zGhRLM%H^GJ5|uAtM2qGHYvhgs-nO<|E|?S?OLMUo<*)AmC1y zLjw0vgg|2lQas-CbQg)gbEMC1(?0SPYC~#z2@m3UxAij5>D*!^Z~XWBulJvcUGCEC zhBEuaGj)pvO3X5Q46Z~a^-l}x57RYlXq*3d;x=|&VMGzs#>AzOqteoJ$h||TBHADf zaq$sAna4MR@e@2R^9mWbP%Zl{(ZBwD+3f6DWvq<_lZ`hO zM&P4}Q#$`|))<|7Q1_G)ibC9$K&866f|6Y5$po?enVZ1sk;nl%G#7IuPDj0mp*Q;Z zy?VJByx_|~TA2Y&5%nT}b!4K#t#x)XF(UmD!Uf^7t<`az;;ba$iH25HQ|t~Ugtkp5 zEb_s-*jS=7y*Lo(-r=yo|EA>JYMp4r1EbW_j>DOhx9%qx*%_AenI=1`yUMb*$LFXm z5R)E6@tBDjBv&L&+2p=3D<5t{vMKEOc6@V!DyqvT>b~|GeA#uyl~KRl<;A6i%kN?L zC48#faS0VwFTZC)GZ9TRQW7P;_)c6~i|^XSAm8D-+s6g8HMpQb}O?iSyt#-4d3?bIRU zd*1MrM%eC_=)A8cXR64ML4WABu4h@5=M(h=O27$-|MP1UU+>ubbK%dV{09B#JM-P? zHA8{wr_CQcXE2P&h@?GZH*ESZ!I&qG>$1Q2Bfj&8or1DwhYOkgx<&g2KP#R;FL{0O z_ORpompyJ~*V8@**v!VE&Pq9pb&=eRn`p__y&kFf_h0z<^$o4Ddwb#wlvu2QYt1I(ZmUejYG1<(9>cs(eeG1B<4WFkhJ8L^@jD~Npx_d~MVqT&m zlA?UMdW&E;QMM4Uh)GI#i{<}JwU~%JMemM&S z|H-fQ$0BmsvhJPZa2jt!%~G+^t+;zTZb_2@;Zc}?;3`J0h-DZP?!-_y+i@DPh{6RJ zMSl8!!Ky#r5m*q)O?+Vhq%(DR3nDrN$W(w5nM>KD13A`Dg;a1EhZwT#A1RqbeW)sz^zMguvoxL zTnuD<5u8rR&kUan>yO)+ClhvEz}ZA*6#*QgM)~TUmYz=4CW7`LyM&+2>A@;iLgK}= znfq{k{o>}krq)9Jm6PSeNmsHBgYP?8au1J)iSkFun^WI=xMukDsJ&aTonG>XimfN9 zwlyQW0`$eg+P9{#5tof;i39w~!>1(D*dsb7k(dy=KWFsd@-cVMJI(z?g5CBR({n;U z1X)PPyTbR-_H^X~#qG|5s&`}Cr1XYq6X)ppFVZkC_k8L)U(GC4bhx0@PO8wzNWbxV zzh!^)!h$I}yHls4VCSS+^&?vU`@P^ztSl`_Xqr(7XT2J+^@vc-p$QMM>*tb`Q4km* zVG~obo#6?yE-&YHJuHmQl5ynmhQf`ZAVvm*)PW@S#nsy#;Qc3v2xi35VM$Y%s8P5l zT|7<5=%~2P0Urbd5&KUt=0TPVuA4O}47f0k!MBX4^zlTuaFd9_4JjB-vEdibZjw6t}S?`~ECUF7h$+-7;kTh;&^5z~*T!v8J9`7?7SAOhBt zyB!@a15R3+=|fA2QBIrL(X0IES+EBtUX7!LsQmFDz@JnhXuc>i&}P|ZV{3~XVG8IU ziF^ncL0JLu z-W0Fj+{-@p_C~dD&K>t~y;70z>UeFtk>dk(>2Jh$3MmcFlPao|NvS`6a%QTNJ_Kch z8K37)oH=d8W(vZU$w2vdUoj=!gA$_=y>qMO-BYdoIcg}0t$;istsNOYLDN3lZm@)9 zO?5-v8H`#h5Ih=xGYP^ba>cQC^l@Tr9S!zN?vb2Yjr++1bOr8|*P%DRo{{+LGF$6- zkteNmu|Bb-GAXuHa24}F;CBF}V6Q`eTRjqmd492UZNObp!X>gH2X9JpMG&?)#c|BT zM~4OMNZ-XD;Qb>H3P|BZ8VYdu>;G7>AQMm!WvNlM-M>!izh*rz45ZKB9$)p7Lx=N` z@Ty}~n1ezYyp#?O3h+p@wsK)704L2Ozg1CbX=$R(J$uBsOZ!)g_0IV%0rTWB9Ai6l znRfqttGSsq>SJHKEH`T(rSd!M=~j{4tFhy>aigr&1{RkD#$SA0hBv9BaI(+oI8+~kpB)3c zCdF3M5FzM7$;og!#NcKPH3goTi)1F8+ zL`erd5WE#$2(hc5A$k32*>RmXN$zy#ZhOIhSlcc?<5JbjsY`@_4EsZ2+7*d3Xv|@p zG@um&v6dp$15}`WHGwtdwijQe5wL3Z&OpjYD2hxew&$>Wqh5gx?Z+GajALXKNEIP; z2+(|F_)cLib2{&SEG)_?x6+KW;2gtIC#Dmbf9`3lB*4jM;r-y3Q>6*9eKVv*$9hpN zouqMG66^|&r^?2kZE)ZxblToJ8WCt`N{rV5u}&{dw1#fS(p2o|4d>p?Pf~EDHs6|< zB#4F7D+mGV=)8TH==hL45!-v-{bt7kMV+V`J}-n?JEcHUHvZ z_(IRcMkoo%2@eYb>DX`I{mN=r@|1PHU`)v9Jm=HBBBP^|S*MC5TCF$dEUZ$IhyC^rf@JJ85{``jSXkOCHTvX<#Dji^-w61;o)~oi z*(K=AZ1=ux3h)~Fxn$HFFRfs0pgiIvnQ*rHMqQFlUyoZ~&&*i#$^2dYgP)%V{3|cV zg&+ePdmqs3J@>7>Zk}ZxQ@D2*kR^f_fViQ_uQ5B9G*x;D)4CN=W9LfM_OkGMkD!E*il<;(v)JRJegO+kjB3kd`dQ3c~z<%O2bW3NBS&GB5pWY;n0J>m9OWYOai7yu=*$L>`JG ziEx7@=>^n@<`!Ax8FEkzx~3VwW?D28YR!EDxnUa;L~zKBa>yfFkf4IDT&Wd&R)49j zs^z+o+d#_WwQ9{UY1U|K`~cpc!OR3wI2nkHdMl;f=T+Kq6w0 zJ8!QLqiQy_*q`~M+0j)QC9R@GY90onzowcCSrrPeL=0VQ5}xCH$0nQA^{DR6Quddt zigaSGQTxN&VnVifO{&SS@v*4t54Bvat9m0*JzvnDy_x@rZY~?@F}vKQ`uC5t5BpJA z{>c_U-i8a|>|@W}4Oi(htE)>RxSk$&f9BFkB3ouF9ct)G5xQD(^vYO$9r@ivY@UXd z3oGmn;`GaF$xGUPM{iJrgsgrPzAYHo7hQVU)$;Mn<3h85+r86{IzI>{gg7i9K``Puw&a`M*ltZdGTQ3h>*2fC99EKv~^VI=*VdtKSfNhB|@}AH6qL zr-^t<1QV=1v2B6-25JOysIpssrCBXL;^>#`ro`&~ZR}fD~R~Cd9-P-y4y5 zl^_ByT)>MeQ1$luHPWp_r*5_a#r25Kiybc4mkpi^;$@BRy@15|h?p39$jbPa0_sFm zXqcH~obz+uFWb0M4ka^lKe*b)5$I5py6ugXO`~4&=*@U1R6LNI(GCg83p8*iP5vCM z{RTG=DX{5JWI!ZDU%r|;$)xAEZp?Z!V!G2~_QRPX#q5Jp8by)sw2sAYodB28`isT6 zPrAf&>qny5W!4rJyX7&4))~9^-to7?ZN_yA=l)Gvwy~Cz$#&&}ZM-z={#CT<3C~1m z^+hG_wNdO~JF<1u*6`cP+Nyn2mt_I7oUvKQ#X~PXIBB?EZmylWE0X>~HiNpP#Cs=w z2P{_yBFLrO+Qg+9XaXmtx*jsv74qy!B@ zWRZ9XP<~EW;iZ8H^9*}W=orhW7%qnDH6^7Vwt53Wl8B8#N`Q%=_Q|lV&U-;SfU%~f zr^l@0^|uX=j!51HZf8deTT^O%tDK63M$-xxsyJ(BXNSa1;ZY|hEo7q>ZU(G62^IDu11iEsELk9&SEZ$N2xK-Ki*~ZAp0b|KK84UfY?9fD(FRm9JE67D zyiAKAq>ys~!H6H?DDTFXiyMrwa=whJIT^lrh2Ap5WU6lm6DzO&9(nULdQjr2x$8=K zkDS$Zo+qV-AkMeRyefr+bwxW)1}|S^}i=z0%iR9H%_(pr=?z* z+QxFLmJbsnJ^zVRVwn(D|C4K zmdwwcdyZ@Vir&iKf1clqW}1Ievy56QKR7MPRV%%wUZ|DudE3O2{UlS3YZLFKbAgz8 zBYr1~)7bmB%h@I5N&Wt9mF;)X1?Ulo+uEtXs_DSyB(^g zQdS&J)jdcCT%wFr&3R!TIr`2;BKBgyUmrvp1?+qJG(FBP@ojeLQQq3gd;F3a<`lY4 zoO$bwW72_o0`f-Fm;tU_-erpu1^7wW3 z_qFdss_gH={Ny4-sf4A<9>w*(LZqCE6x&t2oA}Z&^__s*gbu=tl|)*6x1HnXumSyC z(JQ{iFR=xaATTq0zU(Dv0gTbX2eR(F+hadEE8H#09Txgb#Gyy6;*R#UT}wv+E}QSx{?@8s<;Sss#0OWIk1#W=a1P97h24@LJkkfZC*;kKv(^g)>2} z;A|iki4hrmQdj;DNml`sWx9oF3`zu~M5G%9>6T9ElRk+j!$H&incx;KMDVqmahNLZ8sHWl8K{Trq*<_MVFU{ zsXZHoXbW~0{da3b6p2t5sB3LHCNg0z~cgLXLJ-XZyB#!hnrGrT}YHy)C&A;{x4 z5Ct${cdY zAuFaJ(@W9zE9v`ZkKNwm5UH%0 z$NiN9mE;{xSdfl1x&=AWmbels#U@b>MC2NK2Zi#s6Q5;Dyd@$k8VOb0g^)DwGB}Zg zbtzarvDDPjkr*_rz;*!h11}}~u!t=OM9x?$1oCT9xBgvV!s_dUcryXA1zjxR^Non( z{FrM`!BtFjfz0 z2GPV@iG%7A^iVis#TW2)SW~H|W|{`F?I6|%F3@oJs38Y|OzKniNlke<%ne~M15ifAIDchD$&PgJ&%(grQSzbAjDffYjo z&x{G=ZNcxQdM?UrpHLC?zWE`XK;-dN60Z&Wv$y5+gXEU$v5_lAE8m#wkgg^x=8cR_ z1|#f*h*&K^#RTQ2^)uDRY-(U5LimoBmrV-1D^1c($ESlLoQgr80H7xcW- zd%P)wbasmi;c$2a<>ah!?0jrek-DhYI{{kZby+hv)2(k)ItheGJux(#;AI868xi0G zGDJHP@&eSf?KfKNd!|)Gb+Zp`^&;-IEABcbaV%v{kx_<`LNuEW7M5Mmh?OX)JHLNN zD>Zy1!9o-S!=qq2B#^d$J)`JG=;ffE3;O|BiGXdk*3w(^E+8})tHuSp4#G|ez%48* z@V)~8%;kj^fYK3&{v%CC-2c*7yQ&pU8yQQ2_Z0opvk2aYETRgXl<^B>TljZEI^e^d zhF(%c-(o|qv$3kd;{Q`lAvbmDIO9eTa>0H%@-qCOnz29&z|(wdl^vJE4E9<;pC7^S z8YT3H7)~8Tdn~w{p*bp|(Q^u4{yuBu(HXq5zP?|x#Wz1srN_wuQFxVpDSw#(Q7yoQ zJM^npq${iS(gA(|Vc9EWi+?e|b`E^{R;D7wiy?N3s4*6{yfInyH8`HOT$8(0@q&MA zPG@=j`?9#M64gtSrjZ>-*N;f=#=rb>jL@UT{eH#z}ezK81r3};GKZG2vb+r zs~pK2KnTw0NFO1+**M1x`%=xKR$Vd-J%C5Gbei~NDPGXU0^rGbzbIy?5me#8Pql&47SgqV_yh&8`BKgiL@#Pgse6Jt1Au2$ zvINjQ;ehI&g?1i5Wvq=>$Mw#Rz@g8!P|z22ArZa=Dua6 zYhVDIZ7`UC{uP5(6k%xxi0mYpxs0Tv=b6ftrr7+e3*|WphHj>A`|7Q3lY4@f2h@lk z8&(K3F$UAoIDP+BsQ0`s3qc_;c+iyoS^xRq!BIh)v^&MN4Q z5b}0kk{0ob80xQU`t|tpX5CEY4GC{!)9#3Q`bLJaPOeyt8Gw*oR^yLJvD<8FjHgPG z9aAx~-!&6?XRj-lxT7*R365jv{jQJE`>kDs``!kdr3R_jc5%eZ& zIkeiv+?!ljUTQAW2_E+wFQq?{(6i6#y^!#;=;vg&)5hA~N z+E}<#*M2m<%^%N5Ek{cCb1yhXR3P;ECVmIdIW=)}ZHLkkuX(K65~O1}@oojWVy9LP#TOGeFX=)18QrcMd)2NYS$@lL+ZFDHUD@$ zLF!ztt#IIxidbDBXR^JL9D4FXKtcwapK7>&X5Qlgyd;`aFCn1+K%Y~st2nrmGtT}o z=)Kc#cL7MN0x_}AuUpUBX;TR-mlRr2Fi3jJ19Kh)2Zoy>Ney)r#D13FakBW1`H(&6 z7qR3IvwKf~#Rm5(Dy*iEnx($m1bRV;_Wlp5h5xfT-1|+AV+K(Q4*wJh36P}1Ojh_S z@Y$Q+2%#Vds)rDjWG`N*Wl5{j#hNDtDypnPa&wWKl^Z=~q&TF0xz+bhCYv+3=x_23*v%#s(vD=hsdkoGVi zL(>ZobYp0zDzB^6qZ6+Rg~czfv0q6X)%lcd<5vnv7%cA3k7y!k`hM25JyYY`YM7Ta zIvSBqJoq7w`vvm+=wd^?@)+Ex`a1QCCP2mAZc_t9ZFBMWF9wF}{;!~xir@~=1x()+ z^VI6S4pDGs*gNbT#e!>h8{#e$gOO>Hf)YZr#NMwAlJQ9#1t@h8BBz>+^g`D1uSzIu z2H7EEf8YCh2B7~?Ax=8tP_B0bi@;AHKgbY8j$j4H75*C#R@J*wHN%3Pae8qDHwP0; z2x4Ml=I1p3v5<)7wT72|;y!-&2O>b=3ZOKc2LM3!2}8$%>;nZcJjjhiG=oB7m7;N{ zFI=I|r1DFw-{}g#aavd!4r74l!fXx=95ZNF{$v zOkjyE$rl^l8?de+_4w*1ql%oC_S<|wos}}{k_nS+!jP=3uvtCt59x%6={6FHXKZ&5 z*Se{v+UHs>BaNcxU;GHN($FpsLfFOg#uiV6hM!;=hkvr;762$E9q7%n%hEB=j5k?x zOl5>pp6NII-ASXY%nVH#iS89pDJ zRZ4jPmo11H@&c!Uv3KQ1Pgu(r%Yb-KI+x6Qx8FU7NxFn-YWyxU?eP5wDeF~9x-_W| zgiD5ZOhfXJu=}6K^q*<=Jv2TvB(g|*Yp=Pa)#3TxM^>uPYJP(k2cQr5V1NjL){*~k z#)%0@F3r`iP-hB}qAOr~10571<81CXD8HXMuYpXhT1|q{3sHXpdj@Q%ps^{OJqAUB zV%7~J$N%?S9Rf~E@sgfkF4KotIYfFMeA*x~1<|!WxlRIzWjml!7g4D)ReiTU?TB=X zTL3m*m|*481<~*5_E>@#^C=iq!G{9N0270uw)TJV4uH4oQmCSILSQ{ymJbX(kTG#7 zvVTDl2BJblgF-W&>THowS0IIzB*{iDAcPq;x-Z6-FFa_}H&^lrF(miry{QJQCzEX& z_#31EL=ZJ-Hlt;hfMo`uONR(}Y{bU5`b4!F;@`YPHi?Uz;V|zS+rkQL$AeU!$Cptz zEB<;Y9ruv1Sfi>~FiSLpW@bFKSuEgTOh8VO6IHuT?z~C-Q{xs8%a2rWMjHRCHsz^0 z531ST$>NlE8F@EVBJAMc%pUcUyPf zWY0cyPB|z2k{jO=BN<~31d}LWWsZ(0U;ue4E;v6AXfqfJK>S3?NOcPZ3{${EKjq?5 z;b=D9ai3*;eV)z52N*%hAkfy}HwuWo<1vNlDkpDMbL<*pG&3q3$+#U!5YLSiFgFkw zPwVrnL$nO_PR?<3!G;p@)fFmOnvpu5fZ8H=Kg3)I@Np>gL5M2A_k?I2nw^^ii4n9Z z!rTBW5cp@|1+Hjplxte-x#%_HsQ%iZ+9dYe#t>R-5JhAlLxV?@C_KmF&#dMrGMN5h zkO8vucw-n5^94)SLO4h#TsDTlHu2WIett{!zD^Ic_Q4q!4qRS=(bI7pmasb09T+*O(2px&*?<+VZMHSu)G8X0R z3}boRH#^T`BFkNj-j^g19LcIO-oAeZj_BK_rYk4^U}gY<5TeB6!^#Z3e*-|_Lju7D z4ljFb85P-?=f6&1A&1W=3B!JKxs`Fv>~pol4znvvoGh#*pOt&WV`yk%8CRWk>gTbI zh`}IAIye~N$h(`EWdEaV_Iqd5|W zu@_GS1fp{3&J^QE2w4B!%^|wl|MmJaV#7J9sE|JIhx$gw1oQdMm%2|NbPoa%fyw~A z{TL2u&FHLVQ#aEUgN=|>$#`viWR1-mo*=!EM-xTXoLHzK9l`J3Nq#r6h7=v3?`aB% ze?Jw{|EUbT2hbLUD}0c->35v67_jmz3|)4Mj5?7dz93X6l$!hLr&Ui13)YacZnf$C zu(r&xIQJN`w)X+Lnojc`*gs5e8(Z-Ponv99DYKA0ajjr-2sXM!W8#lx?&TMk zT^vlC(jRX4U%vutj@T0g6&?mzd>YxVZ{Ikmq8Z@pLEtv7F+dfE9?%)_C_KD>b8jzT z#46v(e~KyX%ZIf>F77@q1rBtLcz?AN#lk_82@5|5bCzDNB%d0aAZKCru-~*;*bytQ zuGeq646oM=J1krvDq~^%HiPboKkO_mRI;P-FJ@=2VJEtx)?y$?fU5VfquTqD_a6Cq zAVYEzs3NKLU72;VQfy1g{`{S}b6l0gp!bm2zD2%7q`pXi&5Y#7mIp66_sdpcWPl#v zn4X!@fms!i$^rkg;|7Bgq8=Ney0uQw5v0KEuLSkAI#zST&}YFKA);^qMN zZ+VqUV1j7@aZ@F#G6pKfQ_)DIgyF}Fo_HG$EMjrTCt_F~qD3P{gF6Tl2HY<&vht@% zL2n%FKJVc>!~Bhy5PI+E@g2ZTX7s?P2=N9Pl5DHHK_`wAUVNY*4d?m%Wy|vO@-S{7Z z=D6+k371X`<-(TY)6Tg* zRU`A;6-O@l7?Klfb+c{7|F~>?3ou<0UujQ}_+yagi9I9jAbZsu0p_xs5Xb~aBKI(; z(qO&|3-xH`BPAMqf5`c{!4ln#tuIFa`E8G7M`;4MOEjCJjER#N=VjqF_VXu(H#A@* zUu#qQQ!-@%w@bFevQ|?>>*b9eYr#A@@9cKw=V!#I#hQ2Tykh})^z7G}cfo_`j$csI z4twmkB+fjjaw61bp@TRHN8Uil?^+r!Py-R$w^`k%1nyM{uI40YNcQrRJEy=~J=sEQ zZlcS&A8u6>Za#Le`?Hyn783nMwE0DaoevIm@WZ9w*jAM(6^*sQu1x5`n|5-upCMTk z*jt#LA-Dh_6GVB0zP>(;Pk3lw21KJ)cy(*xD+3V@Hc5n-f`uq+U#+2oUN;qxO~ic$ z?~xd&i~k>^0FDxCOS0RO&`ba&aJ#u{T+0NC{4vlx`yOPgGBIyKs1I2L0KOImy4Of1 z&7e?D+qKiryMVD0V>xCMUknd)hlu{+%fZDLej(SJEf-V18}7P_ZWJ+%W( zsG--2%of?4Q4lW#M?5dFTyAt#51 z*Y3`(2Q7=3|Nhmsn>>YaBA$2zOSRw`+#s-(;6bcCIvf!`!qPl<_|tBc)%8#~rDA~5 z*1Y%#<4FwRyzRuaUyeH-ylS}J6BojH4#zxyTd~g8teI?y*1sF#Veik zDW0~G?&>w?20f*`W99(0kbRg6T3Y--cs%pf`=YS4=4g3$VrXJ*I#X^&p=kftX;7AP zfTg`+v}5;F{IM{;WJ&YnoOg;H5h>~R;kggUy&9XE8o->tF(P-eSzdv3CQ>?jazwuDbu=5Q!vtM5R8*Nm|LF$im zyO-p3&A3nY@==j##M*Wa@m|n?6L#>fehq#KjchQkvYQ(hNX1~ZQPtOvnETDG4VD;V zBpUmG*UM)YvNZSraUACP|H}ho=gPp{m;HP}!-Io|;4M3Vcmb0d-O%n8j1F#yfv1rL ztEK4=Y>Xfn8$dJGmoRlQDkDf?X>A<}m3ZZlMh*5Q$Pt00P8eitk;ZD;+Pg~xPzL9$ zot&b7*wzrk0?M%4^16EhjuL)Ev>|MqOA-e_~v)no7)zz=loMvx}&Q6Z~Sl`wS-Jg4uZO`yb>P< z6e89**N>SZRU=lZ;vw!TT3Y=F2Ml_(R#S8oQL%#-y%y$Xe9+(Bq)b4lGqkqiTAeXx zmt3%Qc}XQMPOYw?p<-xgYZao28aF{%psm145WgVDCDSPyoO#BycstKOHwII1n+Y%5 zx1^Y9CVuFC(Sxby?{@1|WrKB?z7V;kwHy!eL1y?hI}uTW6YuWHSrqZVA%UNZg@uKn zau7>cQxK$>(mUDko7_0Tc04(>HArVldlXXh^ ztQ6y^E%uMsM5bjMRbl;RJ0-@6D0$zQ?!9EA$HuO4eT{2Ur2|^FrM~!nxV=`K`FhP% zWny{`SLk{DE)4)A0HP#;=I}KV6mD<^jSx{I_)1F;e#nw;X~9DGV~0t?gc3_ zZdp;vh#q{#enyOD_K}^RQgW4#3-~02K61vw*++^qNlCeet2u1o(ln2F7WMRO1E`87 zZ2oR;{>tNL<`5Phf_&*A1cT2&z!6WY89sDcQd^ran8HJro5(K?0XtjJO_-aDk=Sou z&aR=M0Rqy>`uh65UOme+m^Fc$p(MBiYTP!+`GQu4u5)&+Ka6SL_vxYvMtAx`hfasO zLPKxE?y?14NiZ)$xf6h8C5RIjN=2YCI0NE)RW&rs%ay>_2=R_A{lOwXKu`n~R`5MH z+cQV3RNM{t+&3KhEM9v}?%VCF&ZmorqwC@(5Q>5jnB zut#!d=aUqky3d>kE-rV$s7BUq6p);}-TXW70}HdKP)y7to=V7};Sdy*v$f^?qD+Y^ z(TDtClI1m_Uv9#~`{C{CZw^%m+$LIImL9k{F%}=36?JqmW3Cfj^gBr>SRB|dwAy|4D!0i?>it{Wn{U z!otAsD=OC={(nUvM}~{xp9Iy=P+Ak8+cq-fx@xS}WZrc=#UF%!^fuvy$O1Ow=ztl{l%wyUBmy$8u zoxrLG#yZaksmZ?|;3*L&C=JRjEM!8Ul|LQoRG!Pz#X`0k{IH#S^GyKJ0gc89$@Vm| z({{C)R$b*Pt>%X>J=89Ls zAn=p=vj8@v0`)LaN~6t>mwv7HKE0gXs+nx~n@v(vv+#-)sR(rw#S#BQOe#*8x(4gE zAE%-BvCt>UdnJ0ea|Mlap^tW{ z!yP-nVO3ExgP(FS?_BviI>WX8w%+Wwn)&&GKcVC2PpXa%Q<~VVOpa?^yOCj&@M|xg z@WMi}{PmSNRn4N)Iv?Rh+~eKoJGa`6KDJ)=zXD5cx5v^OZ^aq5NIJyD z%q20CJl69%c7qS!jOhL@Zu}z?Ljy7@8YoQo5dNSH1tPE!=U1)6eAwbXCRn;ii^TP< z3NDa;FScd?l1)rv&QHleox_kyJ?}ebA|^(gX!y`H`tNKMmAe0_F@D4uC!<$1+Q+!m zkq9E3kOtoiZXn#GK6Jrz0$o5q8{PVEt&U^Xf))sdr#GSjC3M@704} zj-TM^F^%DR^n%eeJ8{{yKM3@ss)mLyfKt2n9t#Zx9zob|2LRv?ca;O~i31TwcucwbDRca)Z@ILx=HnGHt)veNhp#E ziCKT7&MQ*MLe^LbmAKAfOi_&uYIU;f# zfw3_cKv?&WwqA$;miX)q(U-i9<5UTUZNG9wk6#40nf(a4Lpg}0XNO4j*( z-P#_$CmFr9#RvNrIVx($vuEScGG_T@uO25gcXfvA@@$iy#U%Hyy|v?p7nB4-m;8BB z23rn~d6VQ@j|Ez*kgbKgej8r*`|}}<>y%8c6e`_YEBMvh%Lj6BVuLbE4c2p|hj#JW zDFTXYwym%Dg17bpbk+pxm-qXxUTSDG8{iHOV*6aoi5NjO0F3_ZFiBw?{Gj*pr5elk z4d{>SOnj_=|(U$y!uXTFFxBdtJNLh=a& z3QK_Vwq^H|IFf2FO+Pbpm#r(MIRv{!*HYLYcRafO;h4`;B?U(fjCd_4IqX$1HNwFS z72nVCXvAY_Wbwzwss;vGi7#@w1ipiT2)F=~3YmN+jIkUBCW@#ONUi|=ycFe9$Bx^E zq9Eb@B}O9d2N#bEJP$p-G;0dW)bb9teEP*`-@?e|7P>rZr_5NCT_J9gbfjZ#r*^I+ ztrDjkNB;0353kF*pg~!RVhU-f1U_02wz|dyLiWLy2!Rp#yV}`>g$7d0HX}Elop=e@ zyvMhHNEeK^I`NWcpxT_QNw~RzDjo+Kb_FwTF7u8udu!xXi@3<*TQv8z4Vnc0Y$#Ff z_Z2Iz`7%V_X22Tf1JiNa{`KBXA{kF`#1e4!VGLoxbh&tr1?JpaB1L6o8xR%msdBP? zl#Jt}S%t%tPxVn;5=K&&-IFyq9R2}d_?}B|FtNHf0cEZ7K65~%5r82fFRvR3ckNTAs*!8m(nd$+ z`0Kkg@HE1h1ER%B_!z+*Ibs#3&C)e6@WJ@RDsl|;E`YTx!7W@=)B%yM{T#4Sg9nNO zmV>z8C(e-uCS2W>pOUIGCN*WX)O~QR(FzUlIi#21$_L*B;#5Serv#EM$7%a8-M*rx zsx+NqgP+Gip#`W+kh#N4ek{;@@a--DMVyd@4{^yLuLB8ZR<vl?VaKDE!PQkPdL?pD z&P9U;O-*AWweEH=;NmmQo}BxwH^R`*?DJ^LE}F9c$eAkouXiQO&FS!kAe&v>gmBWE zUWd9H>bkkB{ehs^J-f@_uWm?yNMkUO*sEP@AwMnhpS1b1n06wyrjymA|8wECSv;z< zuBW1zgG02)Mb$oj6#WkY##E&|V^QL$?h3H0d^K=xNd1BiXgpMp{+M)U#7+IKVIHhX zslp_hV4l?2s0&A+7|hL(wtsT^=cp|Rx3auk)X>l{dWeSLj*5l`a6Fu|J!wkxl`Jkm z@IkzMnD)bmJrm{`oE#;&qN#H>O&l_6KI&tJ zbE)lpBs63~K?3+Vz`-ELd1Dpq`#=-ojF)#6w*3QOJ!B$SvDRREs^ewQ!Wb7(Ae7HtVuT$sa z^BIm=U945z&sHT*wH|qUdHwr4^xCg&c^SW^W}^P3lEZxCVB|y0{E`W(@a4n$0ySQH z3ULkK-J02_1)vLezo^h_XGQx29v;8;+QqB+#R>X(TcYqaS=pH6Q`*o88``At%I^?` z`_WSJ^LWbgUi*kmyKBSjpMPy5^LI=7TMhD+HJJy)sWY++Rf2bb%!Ae% zyCe+EwFL#eR=raZsBXq(ki)a(ijNZ#DnV8BvIN*1Kn6f^nkCd4H^P)B4V`5G=(7*G)htSht3+C8f;^(?>l|j!ZP=W~m1dP(4WJ6>-!T};>QOTF|Ns}L#p^tnzAjzn1B6We$+5o;rzJ7Fi4s_k0RsMtU!K;}eo}9tyxus$$s7bV@V!n+kUt;}p+2or}GnqI6Qtw09}oB!3+ zVy~sT*L#Uf*Vl_?bG2We@x07DTO*^tf6J0zKL zoa@2p&HC6sub`0W?Q=0mP1AzS%mB<2eq+>(aX+eGv$>TFU8pc$mU1+?(2JeUV|Uqx zEGJwS8=>T3zdid|mDtjv^6y_)`5bKe98aH$F~w)Xq7Kek%3Cn!f?c~CR01$3Svj#< zoAHHrns8|z^4BvJYrf0mNNIuJn8^qO>eUs%ORTBfX>{>&Bx_&6Vp>>K1otgWw^?aF zSw0L|Q~_{s1OW*U0?!ApttM@KqHQaidE*Idk^-r55#rshWI4`&NRqzSBD4L0Xhjop z;BZOdwqHg#V>gbWKN*{D4-(-(Hp2-3R$H5Bi@6@RXq#73W>nDWUmDF+$Y?&`8`Wyd z5vvEGEC^s6A>I{^NjNmRZE65;kb!}}&SCy}f;r6TPWGoO3N-lOE=q$Aly62)qbP*> zdU|9GKCwQQEjGdN*VT)bca`0Gp+ZS9rCkGhvJepZe!nGZ@bYDLRaGoJ4-N~>y=6E5 z%ErdWzn`2C9D01)G#DQqhEosLMpnIAxIU9oQV`kMAsq=1Xv66SqpUutaB)psLIv!N zteczL!lNy;hY#(+7HTRu7A1CeZ;VLrImLAE$rk&K)xlI>zP)r%p0a7b7 zNT3z+#;J7M;f6aOBq&QIbqmk{5SpA!8pH}%!Hiw4K(x%|a9HNcOUaZro=;gX-t+Z| zjCY8}&pU{yFbz?VCNH&Pz97c=vG!B3ze2F{{_;P~l{ISVx0Sd{X-H$b$4g!dS(l%) zkOfi(g28Cn(qeEoJe~$Vbwr2@G>S{vdV+awIQ=X9;ogc;w*CF< zF*B;nr&4w3EoKC@u_0r!pqO5GsY>=N1$wRk2B_xce^RMiBDpu|73eE3AO3im_4Jal zyE(2uOBc$rzkGQ!?0z)Gzr<(HfEkTVhseX(YVgEWm@|k2Uq3*lxHtML6neXpoSRWtEgf zq^GA-4aT20BZg&iUbuCIWx%QTMWkx(H$46@dmVo>w5Q_1Y))ue$Z%y;+}9r0p~8cS zH93L4AEIOdpC0yE=R~9i2zmbj7vI*-&dNX%CsZ0nE~HcZ*_(r|K}?vNfpY*c@dxM1 z>lZxt)inq+hQTdkVPZnAQmthc@u5! zZITEJ4VeT?5_xQ2W-N|) zZU3}IP8rouq5W9R&5O^Z-1e?jO@pv?QJyXF7w*l$9CS&9!&=n60yZZYmpd9gSd4LwTWyRV|MKk`X)X<{RTde+$${Qc{vm&M@P~6V~K>*RS$-*Y_1!l@QvbchQkX9D(Ba2x6nk&HIV6;<6aRYVWvu zZd$cQ&iyX^Yw&Ni4hCd^Q(-p)?{*Np_fUcT!L%T5rDk&VYXXJ!SIX^J$6<^Q_=u!Z zhq}2Q>9O{Lp<5uzgy9_E1h{13H>!gl`qrsra82&(%c;@PZ*c8l%_j^|+MJavA`$Vg z(A?@o+M-AQP@Qm@dYhntLGI1qsG|IS!v=+c*A^|1Nm9U{!WRQ5-Wk3aJZ*sgXOCLL zL_L(N2%W+m7^nqgN!x3>U(Fsybw^mP4wk6rUL+6-N%3;8=!KywJ zBy*!zp}_ym21&h8T>mcK)`rwEXUZ}hHx|Z^6~x6K3TGr5{m8hP7fj*Vr^Ng5JZ{nF zSP?FR{L<19v6jb;LuMSNp%TmT(61_jx+O6GifqZs^g?;**8BXzIpqQN9YT`qK8uLw?|7r+mRoAtN74dDbQM(jLiR_0bjTHP9PjV!*g7?_ zf{uCAbS4;EVd@}|d>q?b>3@R^-mKnQ`?&)TLAZ`!28BlmY#gXPpIqke1i37n z3_a7aW?X$LA@;eTAxW9R?C-6upsGFJEJN{!#9LmEgyN3DUS5>i#GL1ATXYG;BfN8- zz`-Fp0KX{r{3TN%;3}i#3!BKx!$8GcP%yr^HUI|7>A#f*%fwts%SYRm(XYoYhZ0HH;pE zJ{)iWNCX?+#&=SY(5{Tu-n>}8+&YWK3A}U2H!GC=I;Ue04B(<8Ooad}L|h2O%OScD;B*A?mczuswM*TyukT!6QAsIA zj`rBR+Sxdt|891LqQ3t8-zz^z|AiY18)7`B?P6pHN|2e31HWSt51j1*API2y(y^x; z7G-$EBl!sH{@2?Hwj=E5QnNd*Pt^I{%N&N;k&5LkK6Y-%GU%~_PtmN3r1Yir#?J=s z!Xk0BplhF7RY3roo0=X!duEjs{!b`Ff$q?w`5&LUTP;Jp+?6@(T``#qQ&ZlH_EwSH zwYXn%#krf=i73YWAiZB`#1W{=WuIZhG3vit7)`MN`7;z>-SGSMwBY+rO-P}eN7T|~g ztf>#_G$%kRhNk0@Tr1D%vF4qD({&)r(OHO!4u9H~jyCd9Nq+eOmm>(R3=!usIQN~F zzcZG;v1ff&`ZUh%i-2#7qIJ(5tsULurH9MU;dov>ZbOo>BjJ(6!Q(ei1x<4Yp@CK>nqc) zG!Rgd8!U@lcl&pOhTrUc1#``r)+h#{C31YQqUs3Jk&;)|DcSSFqD$dP6zO>S#pU7a zg)_e%Q1rZl^+=H^9>NF!OJM_Y89)P)h%`zjSot(_9|Nf&q^s7xefDIV4rqV|2|1 zWrq~AIN@gZpHhkQ$YA-(Uqt7SYB-M7Y%UKhVNJLfurRCq^Ry82Drh?O+S@r*+I@|( z;T8AoAJXMKpGe{?&-mmd>6tu7l9`j!$P-t{Z)UxyYs9-zCI zq8w$-xuUWX5u^XXdHdkN@m{!jjc&Piw$J;#lZq-Si`sljQMR{Vwg(d7k)5&3ScB(} zi~M6qa4>|L@bkP{0Oo)~g#cShVR6`%-@d+J!zZLktGZQ)Y^`cM|O@pfA-FT|*~ne|!gL&La>CKcic$k+)rIyC+#e zWAQ^dedxiYj;dbMg`FG9=|5jyITD6rZ@HMBBj>mNhwRrkpl3Za1w?e{&u;-}@8IZr zlzbN2dCO_y^id=83D}1h|90^lbvc^!9_HHywz%>S0)ypw)JtDbQetjw+>V3^Bc(c% zdATIwrs%U@lUU5bnJO#@t%dbiuCX{Tsx%p&5Kbnx8n4)G1?8*6Zop=n$F;fIpS>)7jce0^v z{vwkWHsFuPCngT3O`{N2n|TL-m&poF8s9g->Zp^@;CW03(X3@!w#5)3^^6onA}FGI zRfp(QDM{l|7%Ru4Ad)8#umIXu&=0S|m1G78JuvWK*lPfs00Jy5U0vg#yDforH0g^v zQzxWP4*-w>Cm1A>lWnN9hMbg2rwmHLpAnGJ=6~BojX$Q0!U)hiHe?KyS$`NW8F|=f0y;de(~$dHH!MU9w<^shUw;YUPWq1)m=Sy&AYfz zqKmX;=hcducx@6kX?ku{@g5*Tm%X2~35i_I<0pI&-$} z0`(81Mk?Rfpzqm3KqQF7@IWGW&Xygx7|O;rsr7>>yz|HI$>}K>H`1D@?yrr`85uab zLB$O-ixYnu#uxyFZ9rY{`Ckjdp%sji^Y>*UCcRhpuxXS~7epyx*UC(F-3q)FC_~pc zFj^un@#>1u#sPgq*L=4U39c8XX-qL85cnw4tJq9s+teE4YOL?-nr;E|6b9 zUVO6NHZrv2WkTQadsdsj^fEsv&O=a%EpY`Z7nUIQ#dNX77r;YE`-EOJgcKfxD5wN) z{*C&Mb+!PFZ1hA%Q4t$3Z3Q}0Bu&{ERIbf(4wVAjLQ4jX ztlfB7XjLAq@sEdnjSTCY?#w7!lot}Z0zCjG#2Rhy?38PN_fg)*=Xr$#>AK)AzzquW zJuhvgMJ2Y*Q@CfQLsU6qr^P~a0Rep8r&*fc{SBUe$8b5hZx#vBGZ#02OWag>eg;dB z)w4dss|o-0%@I_|p_!sb-;N$ytZSHBTic(a)lqo=JAISo%%bY)SlxoJS74>8LAcDHXB&pCO4&tQ|Q;i-&j~;%zt{Pfc z*q7WeCf@pce-4xuSsq_(|G99Eo%iauepJ&`nA%|8pgI$RtH^3t`*QeVYXijn(25`} zFMoGfF5xV5E`I1D1-|FK4rRC5OAi01EE7%tyQENM_SQ8 zJ5fq_pkYE(Wys?Zr}il48UWKv?Li11yxm;w;143OS_dJNN>82`z1>JoDt6AzSRbB; zDIJV9lw4d~pu3Oh&Hkmi?{3>w0?!F#!;LO1q+7bttTare6*9+<512+2+ThH#UhlMa znMS2qczGqCEnGaMi0Yqa$G&_|mnA*&Hwj0k=8!97aepl*F+H!4={*ZG;RE}e3l+aF zDve0Rs{vm%&lU3Vo;S@hE4kQ3IsN)ZxW4hg%C5NEVvHDK)<{T6Ej>IEdV6))48Xd& zEJ*Rf=~9}4_ik9`M+G{6MBI`s2|x`p9;KJ?)zr{*Yfvat8u-OaiLpO;BXwaG=krID__04;LQ!f!$>h9QiFRT7aO z$^Xj{En_(Lfu-It>3h%25n|9hG9Hn`YP$@2K-g_NKKC!8 z^*cZfiq2nk)Ze>-9s|Tg2@nQpNQVkbPnrjr}o%iUX)s4k;tKF>F5^K&JRaM8A$57?L=emifub<}X`f_N) z&-i`C;Ic>B7L!#hT9C?IV@*7S#{7&^_#E-HD8g2Y^LUM@U`>131bcM$^QID3rXM+| zC&1Qd9w_#x-H1};T3g4!VExbUd%3yau&_>CAP-lNf?cy{qFEc{QG`bymaU)^wF!u( zgB8C8?*E>I0BQ-9W)ZwwsggTHa9a}6$Ql_x9%w!1xry0G_x6eZv9I)e+j)0HcPU@> z>OzUOf{P*=_jcq!nuiT~0L{pZXE;=2yFGv0s*(;H3{{#Ez?NpWs-bTe^bz2lP6Hhd zHEr|s&l3Ems@XL?b_f8!2Moq9D!skrGA>4Tc6OJeRaxPytrtKC0=y5uM{1p7Gc~77 z>aXAb-C#1@D<7x&i9W`9=SfQGdXq2nbd@X%ZDWEn$W;QK!h3JD1TxEN*%n1;g@Xz1zb8{Bq?z+ef{SSU+wvmq5;5Pe}twvFE6n`(LnRq}0bP{G{Xu{+=N02G>#CfVAW0sB6} zSO-%6%8dGyi*I&s8T&c(YV81)COp%fT1aa{oY+E5^RF8DSq3$Xz9Rg)STy^ ztIw;lMhLgJN&hzapYgz83~15NQ%=snu`MQ!nDGp!LHDfjY4!Vdd8*c+;v>ctbaalN zEO0GmHV^94xfh2i86Pm7CKl~^8BG%nyS?6=o0L@7bhY(;?v%G6R;{>ypY!DG1&5H( zaE+}Nq>#hC9=xngrw-}h8XB^oi-2&C>!iX$wT$m3W~k)$c8~7zqB!!W`ESByk(fGZ znrs=Ri9|1Q`75K+&Gv3Xs%mYu=I!atdF#%l{BnM#Vd40?Vs;**IOd8HBC|vsj`$&Y zbGm|`LIn&=Wvza};SU5trLXo%>ch+irIf#52FhZS_9&Je5&i?Fgr4dox6H1CJ`N&9zQPHr0!$8L-D z^M~hbjJ-*S#X!fU`kJ#KxV4dCHntH?`=uOZeMsve1B418=3S_8@r4qkZ%{_7$k7nk zX~NlOW1&*p@KbX;G)^J+?|5Fi+0FI5ly#-gXWR6rOnnCTnN|&nswCIe?(Q&WZ3)Y& zsR7_S6+G_%aC4W@K7J_8*RRwHimWg%d{5%shosmK7vlp&Yo|sT9^u!+%)!$KeE%5j z3)HvI?78Q{V`%J0_sriaGk|e@y=H1*dCLDP@dHxV1oQF)Qm2CagCN{^T$lY)1KEme4$angTc1A6b?Jxti#SZ?{|wM6Q0uYdJ8;5jw7v2L>US(x5#S_9R-Cb$ zG*WY&wDR#uMQE^+Yy&Bk4Gp6*89;=L$O&eOXR3^Q5|k!Eh1}MGEApY^*Af`nV9qil zxi6}Ubrn5hriLj&+L1%#mc7nd29q#!jK2?|@B(AiA1GIY{8+%e$XNdYF+@(+xSh`6 z+Ffe#5r9E*9E5g-!tbv!aFa)AFWBH2@oQ~e7NV2=#?+OM^x=E+tLVxwTDCeg*vppY zUoYkW#{jhs!7JS_j)nw8Bx1&?hz3)i8DZqDzk`~`mEU!X^mqqV)@oU|iAyaS`ga81 z33w2eL@_c=9Z-eoYQFUL=HYqu=g0W?`+kiBEr|EcD|;2VwT0f;#PzBW)S>uq>I#{{ zSXQ04rNJ04xd>3DZB}SGF`^>)wjbkYfJ$Bo9(DBkTQ6 zx3sqRIKvFY09+b_91b|5 zw%@8?&n^hIZwJkK2`cS<7mc$CXY$qm2l|#MNTmVYNGIUr#HGUD75>siOnf=Ys9K*e zz)s)xMTvSHZMF@qQ%z)UrY|`4GQ+PRj}Nvv z@TS9y4okcvFHo#ck>W_&HZx*nXb=%P0D|66XULOQx92_?Fpy34G5b~R2mGZD3yy7%^nvvohTkFRHfncCQI35;x z^^6}PY(O;H2c6u152O5F67;M7TL`4I!jobAnMNv37tytW&Qcd7>4`dlLQ%>>zqLgZv{NG6yX?ktq{<)p$?^g{SH8A{C+({I>lX7 zIj7#u4%FDA&(^+lk)3fK#v+sb5+D?BYF%jLYJ-q=aEx?Ax&8a+!fZ(E8P zr+FQz&a3q*8wEV`^NwaE>Kk#{fV3L-^-(2#Yg9$X>l z%7Ao-_bbX8gn(p2N;6D$Fy>#n)sV8}VT2Jl^G#&8GP*ZhkLL+@Lhh|Kl<8_{JcN|A z^nK3UduOd#^M^CD;GFM!-zWC|?Yapf71h4-y4V`C>6&jd4_H|Gc2jq}0!w@j3n+xV z-b+O(&L68}4p z>;R5?>D`@a4b9*(Q(0M|YJxJ&#Hgrluh2_wQZ_G;1sOHc{2)W$vr*c7jy09m zEOTPV2UEnIRE1Uhr0v(4Lr=?6maYl^V}@yI%52{@pRF)8KjE5H3_pOG}QR7x9LD3XZnQwqT*z6chSG z*Zwk-DTo#*?~y@%SH}6#hXGo6Xz4xvwp>e0NqRVRfpff>t4S*R=r<`+j6e6WMSEy~ zi{H*sdlYAPJvxo)3o~Z)gi5qufsfx5ND{->kBS>AmORU(vjDyrE)By?Z!o}m9Z{?KWT zx4Hf*Sll0mHmCsK%1{{NfNG?=Isr0}plC0ZfnVl4L89|hixNE{4L&Z43Rwp4D{Lh| zxX{G}7JKCWFv;#~K~RS5>tAj7W`o}Che+n2^L};7%^n{hMRk{<6;`lqp6T z%clDZ+dzh&1Yw$(jdd^}m0g3|VKf|?kO zQ@|l9B?Z#xQ~4IWxJvBH)v!itpQ6rco9T*RaQ;%`PHwqn9ejB+h|;;jy+VGs=JvOP zGqEce%z#VKWY}s2fUn$fe?{IzlkK$7X`+hg{LdA@&|rLt zl8KR}4^Q)@OStmV;HgI{jp7t0QgO1MFW`5RxVTXrA zwVl%0NO~UWc}X0BI9-y84tOm%07vcm#{DmOdFa(Mrklr;lSFfKFFt;hbK3odZ8y6H z0f%uq+M_U`{f&O2Pfr;9gf+u7&ClB$&*|2)mXJ$RZr{owhC3yxUGw5)e@$d-qPthJQot`KH0ZDIJyl_4jhI? zjvRemU5q55m0j|aX5}F4F@quA)zQM`Blt-63X@DQr1I?&nnI96EyHsb8cgWvGQy#q z%kbtKBW&mU_%%G4kIaSk$pMpME9?{3={Du~>;|&ZX=8`y7Vh37QGAuM{Ny_yxLo9l z6t`T9hChFjWp;PIQ__A~_=u~B@Ke39!B!w%2J2kY@Ma~bh~V0lflqY^#}^KJ&^&-L zG>C?i3vt>6GsHiC{y-@Oaj=|_1q51T5DtQe3OL{KrXZ=;)X{;@id|S(AM1OcHf{f@G_6g&UVQ@c^)yb!4X#89@-_7XoVE` zsa9ue-8Z(jhDGJ|^TWt`dR5g8rO{uC@KaXX-QwaQM)g#X_RXbV#S-$IQ|rLFX7z7Y;XmB0X``)cIa>l7G zH|XGDIqvs$0*XXfP5jz@ji_Qz=v{KFyQSm;vUhM-z~C3Ic2Ge7=c#!HhX5WPo}#X< zJgj`cvSY&wdMc-=<48(6EEEOH33VrU?3=YAPgnYrQ39{1sHn{1+Cz3c7&~?gaxJ1WFs3B1UMec8aKRli0OKm}NZtOzkA_q0+&z zfF+$|sm2e&sDG&sWd+rFOk*QDKvx`UC_ad;OiprNT-=qD?;jZ&QgC;7 z2X0vMZP0$F=R?za-?UOcy)4Pnq29LoS>p{24(yTJczDCZWx+twBRg>BXs>gdDyWES za^hF`j`>bSXHxTx5wkw;ko>CM!Ztkr3z>Cw*QBE-%d+F(zgP)du~AXQ-aYfyX_$UH zu>sil`0;Twc#NK=-iB4^R7GBty1w@V>0#}BW=pJ|)H{`%%~fi3&J5|1GTFc@1W64_ zOR~G%IR&#Te`-j73-3j8K77b!0EJxWSPvi^C`%IN>fAU!M}8Ck@V7=6;UL2Jyukml z1FOEm2;K%(>?Vc(?-uvPUhW5i(#@;c@Q|{HFq_`(LHB#fX>s(3*rZM`;!&#MPg#Ap zx;X<<8CfMy8E>%bL-Z}LjHOT0!s`e)`N?D?vXo%z1jkC-@-B>h^-3mwZmt=q@MQ=B z(y*j{?*@1ej9|_H15Bs|p2D&VwN!+S=})0JcRMygb2AaU+s0#uFHqT$u(t&T?-ZIp z%p-71h!Ihs0rYP%P~ul6ExH3<=Y}2c2+*qgi#Bz06*`@Nz!4C?K{HsuMb11&70@1b z)aX|CE-FfCnR0u*rhix&EQ!|ta4b97?%6~a+j76-)jj4B6a>>tR$iWH6W6$|7_(c~ zc+S&1^rRKuFZmY(pjrzg((PFiM(ePs2*CCC2$O~k4;6{wkpv=6Qf z1yU~qn`akd`R%g`t4h5yO?kXwAaXU0bh_|$xuMEDLNA>Y<8^iB+YMG!xx3SU2opVA z?MTcM{Ii^lHhXqy-Gv&5owU}EPpNtM_y$oGq*FGg5>akZ(br1XyN8E7C)DcQT?%&* zQPm4V5D}FDy5hmr_MM4`(23&%Fqv=ubs&h=ePwlZZLeq15f#e>KWb|NoJ@0$v4Od)fv2o3I25jUP z@@A_(E6;R3r!1--Rk!2{Edf~pbhA(?{G6Vap~hzyGk0wU*9~aTVWR+45g2oRsjZz3 zn*NDtl@K3~(xtt99OvGd2n-F-O-aDlEhg>$r~PHEH7pq-3hGF`Bl=+JmAj+z%}n*vd;{ zqOuu#&xaF)JHu18!^DDK2I6z@}zUfT-toOSk zj14XdF-9UL?B5dPTlP+&ml9rG9Y=T3B}IPj9P3wU70n!45QyT#8paFBT=Ex07S`YA z*hZ*JYmq8cHhr~OkoI<}nN=xkgFWNxs+wy;8}+4NgJh@P8Qj(WZA&KmDur&s9~&D&VZUOu{>^s3izc{;bDZlj6}Y;Ym4ENxbtp=P$2qi&42~ z<1H_kML>KiN;UZ~2IqycK(Nnb`jpHNDHYB^A$F#a72ixCN6Kh}FNhLgd4yUue~_)3 zv*SAu_Y9UMeFAQZk-51rdT9x%f_5Vs(5!c4Lw*2!{V4q zZ6@Q#hzMZI?4Y#km=?*x>ha|#5J&dPf-F3Y8H?=H5?BB z69GnDT*bPuYPGOP85;8F=*$6k1eZ81^FJ?y-EzL#hra6}nU`VqLknn<_h(+-pfIe| zYFa$>ywcvK$6WeL=)3pmDqNDXMp*x4iH_Dts=M%wr&_wG8wc}W{3 z7GDm-p2bZke#fVq|1R`cNUVKYhkEWo1cNkTjaN--cQ?6}b-{HU%%`bGf+9}F)iXdS zDnDQLJ%0j(y_2zw8kaArH%C6lv1`W}v-WkSGv0`1~zqO z!QD`=#&Lb*&)3R376p`G;{b{XD z`;2b(XnV&UzkbmIO9u7QqnZuy!bSKT&|$o7{`2FY?z`{KLzbf~PBAL?H&=7pp?VU} ze9oW3gUYRT49@{{p5=haqII`Ty$=4wZ0KI0@&yHQG(Ct~z;0q-WaJMr8b+dDD5Vq} z9566KN4YfLymV`ce!ZY}I0W6j^v0mg zW`44qL>9BnR9Py@#-Pa9b$(92`}(5=x3sJ*OoG-~q7&yh-+cjrQL*mK$?U2SByqC~ zMvvnlu-!I~w$OnhDA1t|;Q4vSuU|>l;JUj;RsWKm3_znvoz$vIL^Oj& zVZXHxd=L0M24?V0>}`ZgS(E#H=u#DY=k2O}B^bLK{$&ZDI)fP>;vApnCvnZCiy`(q z_Kvqxn-xyt&+9&oe{7LcBC@g)`>t~hbgAGb3pr(*NE^`pyD>@(Y> zMUlN6*P?Nk3U3Ti=nLZM3r5q7OpBzA$g(}UfA^DKJp0IjKQ)Sm0(&CV)KRab`nAJ^ zXn4L+<&+3Mti~vwzK%R9MaL*+p=@{~uX<>Nk)Hl_rS#vO#kqaP`41#m(qbYEsolU* z?*cn7%&>8?D#4)(!$m+>Ff#2YhEY$nQFwm}FO{KQjbX|uI@Z`$Q3m%jWSv9D zJU{=J!&9gtVdI3VX`N~)GIJU7j*pMaVGjKn)o;W~G6iiUwr!uIxd{q?13gYOmV>G(?-$_{I- zjE;$kou5!v1%|K$ zIfa4Yakr@MZb#!%6@yX^@d?<8S+BdCR;#F{&VM36=_Smjqq~3aOm4x9x>~3_P>cpT z^Ob(S!9C;?-|^fG^`75MIQ$#3>H5O=)lSQuBtozg^btz%iT?ANua`~+VU~3EaBjZ; z*q^QvI|O|<=nl9iid{K*d87D-oiTrFGQ5QXzF247z=Pkv&CndKK`;Y=KcwHiV9k`S zJBXNl$KBHHRm}k9h3o!JgFDSlmmix;)vibMBLt3a@5d)-RDF+PbP-xN%rYx2pV&Zl zMbUvHA*z>{a}d61T>qN%z)x2myij;92mm@Nf-_q=$XL(3r_$5UQwzFNSrI1D$LkmGL0O!*8Qf3rjqx&3O4YD zq9dM_#@Pm4UMPV)Kv%%?&^97DK@5GFm6a7hQ30wL3|@Ay>yVL=!5ut2Icf3w@gYDn z1O#qa7}@LEo0V$7gYDvKnG^$yb=3M7uw3ap3$mwIt{*Z}X1*7@LNiMRaa+7v2d0|f z-}?Y5i@($1bd?ACE#x?UFxv)DMg7T2ve)TInwf<~5MWHSp%;W~nQ;B7d&_{L+X@0udz(IgXvxCLv;z8<9L_&?E}yK* zyuDoCrn-h3?gTW-wHTu!QQI+@$pSrPW?*7{ zq@fiO+1vfkOHYuJ52m)-)u-P*_NyMR%Cu~`Iju#Seel>&qk>@+LK@zn(6~5y`}$o0 zl2D=bS44JszD0~giQ9=hVjnDsG^Fw)RZgBAU$1xgDb}E`ExMxejk7azd0%Ij5`p&P zTv|&{&kP!yH9RhNlFI7p{f_(gKnwoJtEcCU_mIlUMip6x92m`vbMO0 zD5YV;!i;6CBjJw)wW8Mj6V2S!_6uLLvf2zdU=0k0JWkG5xRv06+upWoJe%8D>5W%L zJX~ESG$WnDkFCFY#B&*2wYd<6)AKXFeHmp3HgNBI`wiqx-6lcev~a9pK*$lQd4ud} zDS9$0s#Q4EK%A9zq3gQ?GeXd|K-?O*5AkmYf`5){GS7)^{B$Bt#EU5o9ObBr3w%;2 zox*~}uSEqt0DfW;C8BqL?@s@uM;+DA!F3B~AURDP$i5KSZHId0at{L-|JYuUnT2F` zDm8x8C#Ozq9|3kDejN%#rc}45^FI+6u%7DKk13bD>cF5os#X)qw33X z(y6j+Y|R1Uuz-8tPrOJ+La)~iLsU5Sr0GsNVKc)E# zhPPA5E8-c?29Oo4FS6RPa!=mMJl5O|nY1A>K7?QF#s5l4Lj1W7EdngK6<)ri+TS;P zp;CCquO>y#+Z&p6$cOwmx6K|tvKf(y*`b_ZGh+3&Fu$wx$*BRUCMdDM&RGU` zL-AZn`p|<;Hq+hh6I#`4l+8;M0z)bYLr~uXs>NYroE69dyvbo;h9n~(fu)*Vq4T_>2PV6q#l!#!k4<$I)-h_)|xeuGGyR9gGZeAYX z6u3av3@`-PtZ|YF>|d^>qfQo>6lL8k1d9Q9c8Awp29&Cj(Cm)2lx}wI;kfHGs&LX?&I^0~SxJRH{1b8LVX=r99v=>=xe599M^+psw zl!OKuM%=%nL~*H=7i)^c0aerVv;YV_BayRA28H=nJ}g7ErsY!<{^^Ani0tEr%QyY3 z-buQ3Rm*PA!mI&}{V647Y4Ga&{`ulH`@PNbh`V?=dncaca4`Y?;{)6#Al!6?VHYlz zzgctf%G)(RBDwi|a5|-WsHds);zuGKB+#5jFYH`Z)wD^I9$!#hbvCU8 zKceI;6+>#D^8CsZbXIw6S{u#yCe=Dv^`nyESW#I;g&g-iy3_%1zJZhoMok?2{HACO z2&H|qH!?!EMK%t8Zd`ft%f&l)l}Tjr@!BEBi)KKmcI}@Rr3gz#Td3=;fZ__l_J~$5 z@qmv#!rpR=2X;5dDA5twxn~Na4RWK{!@mfMvGu5F`NQ_KXrl~Z%EDN=Uify*%GAc@ zqdg#-I^JvaV62^edB!LFZ}A;K7YOSvC|`Q-?kwk7vKNQWk3lhPiZ=~UG|WNBKMULr zq+7_#3RaSol(YnJoSoeO<6x}S7onbpE2YkuJInqJ@ykc4YPHthdH_X&#C1ry>G@kU zye&FpuR~1@XV(e2oK7{0L;-*R+IvTJ4jiw0?|w#}MtktGMbQQR>ofn{4*hTUml~(+cfzMx z!k}sFpY^?R)L{z?fL-|DeE~Lrr^D`fB1G$8f3@8p6qLp0jfkt^!9OY0G+pzPK1|x6 zL04dkJN?kM^v^$&F+V*~AMGzdoqSv88=irj{W_wX`0c0RwU2c*zP+pEMO0+OToU=E z)ABi7ux$7_<_fax#{3_dcc|Oh`aQ{660RC3MG82S%2L{mN|jW{Ac)5hqG1wb-EXUn zGhWL_=s$G6vC9yUd9v)IQ)m<^Ag_05VPO#3>QAXt{a!3#B?^#%%?^Yk;0GtB zrSV~iR@+P|b7%a~mC0lTRsqU&fC`e^a$9zI+T-^z;+LL0qUF$YS#UbQ> zuz>4e4ul(s@J0Y$8tnrzbP4k%kd{sq>t>ad3^L}#Gt&Ts%n1^vP>xGf>RO(Td;L6A zGtb<&0V@*%OUd~7_`Mp__OrZ%Ru{jq+1Zcae*kas+fsobsM=xdMHeC#O~3uz(VscS zxvxq;Tj2Mj9Dg8kh)_l_L^u8SZ`rriHfO;M(_3C zj@EFiXS$rG;4r%M+6s6p63Mr4P5{bKcvGOElwbUYCc|B&X&%cd!rLUpWO9e(GiJ8b zcb`M6XY%r{Abkwo@x79S#H1OoKd)W_*)Viw3nloR;Om>5#4t9#3xf4JurWi$7b0UZ z-Ks=RO`vl{QazwD27qF zzg&(fB$}B})`~^hFuOQ^@i_3C28GL~eff?KPw^xVc ze0OZzmz=F^l$3(Ga%h7emXNe8c13EW51vJ=xpNyyisB<6VN(<6vs-S)z$JIHla7XT z&R>-idO#{6we}%u_j5jN1kuoE&p(gPeW>Pi=LC0u$Dkx;^YeCSY2ZKtUKdb?CCEk1 z^G!6(UcW|pY&p5O-Yx7jWoa7lJM71R%Kq*<6-(jqHcIbFM}>G(D1cBwT|n>Y*m5I1 zxfaj{FM=l|D{z$!FnOCX#r;Al(^1|#40Jf#H8nLKPpkh2`H|?D0Z?yCPmhe!--_a? zx}ClTXpZtHxT>Jr<~-OsPG*#PMAl)mSV zkWvdO8vtYse10y=NK{L=#)|zuld-IO}8~226~k2qo?Y4OkIZB#TAOK>UWOk53frS)2!- z!)%lRv~BhEty?q3eSPmin)?vu>4W+&y6e-KAR+P@=#>Ah8V=0-<)5DPv07vtq(85M z0$JDj1Tkm?aJ0*tfp>QJ@Opg+7jw@|OxUt5(O~NbUqFA6b_2r9#j{)P8q;aB&c8&q zNH#zEt>-*65J=Xsd>!C8P#r&PYkLPa8*wF({Q++4&ppC@U>!puO}C#PqP=+rp zJ-bIafllM%Zi5 z1XVFU3Swm)i)Btw;dIxzbN|3Gc4nI-y{Otnt^TpcP~-RfdNmNRJ3DisQZQO12<^Hb&X2KyK6)X`k7 zKfqH+gjiDdL8?#Ix-!F1OaOW?@TflffS2qm#K+eOE_8q>y#e_G3mlBE1?{q2RKv5` zE;acLRQiH8O41S&R{)=~G@5r!Q5CFax-NP*m(Ai|3yQKm%F2ICFAYXj&~+>eRVYyIi%3eEC&x2=1n8im|bb+~?U*2t#2Qnkry=MkK* zU1vF%^bILF<%&>7fxH&Bh)drd;9}u9cf*U$&h6Pf2n-cGoX||h*!r}e;iKHi%c~B| zq#}hYZ?|q=4z-bAUT6j=qWwPi2Bi+PX%JWQ7M8-OC_=zR$zqr>>pyx^?TD`DQbpgxmc zx?Bd*4^7H3YIOXONL(PdLD=-*D(k&KEKxXY-o6$LUf5Ya+VZ(gF$uw#c+1N-!O7+X zz!)92Yq0yPx39Gyk^o8cV%1R55r;jMd9_w|yb_V=^ty|W=osF6SVKm1f_I(|wogW# z;YFsh*6jsFV|_z^QmTxS>Rzj=YyQ^ivb_Or3sd0MDLjm6H>=E4p1;#Mt7N=wF*5bY zyPdU{Qz0i%Bpr?yMyLvwSNe;+D3jYOqFE?SLi-=wyxjrgUdUj31-@Lx5n9F@z0slR zf7i_*n?Pt@WR5V8O%g>bhn z5KGcu1tCD1$AC2%Hk|Cj<2$m16ZzG<+GgB@HeFumYR z1MCf)dyZQN8@c+-&nd=N_o2W7_Md1pJ$#qo286o`2!=!6xtNzgIe=Rc?+9O1goO29 zEd902IU9v@4mH=5Lam$reyZ>LRcY@oQSd!%L9%=#hT8c#kYIQt5d9jm!DIvEII%7~^y#-7BqPX3)$;ukgm!+qcYS7kM}=%iKo)a~`W ziu`dr*!!UGKZR3 zlu-?QJJ1q-tg^%o(!v}yeWfw#(~JN&KCMb$_A6?6og@U|Z6Q zDl7||IWaKJp*1u#)L&hm!CYjqdqcJFt_%adGTXSw@!ZfY90qC5+NFbm%IXE5WRy!H zWqb5%6Xl{(IRB|M+Ly{^4NJ`&!o@T8)-5NNaGr0DI?&HKmG=z zW?<8|+?d{Sd)L5~km5=*w(bJBzuw8oPw4rF3S|IWdB;Cmw+LiQkOM%9f}e?~sDZX; z{KXI-P{{qLRWT`9sY%|ZWd16>X;bWfHD4SVEuIqJ>YZc#8!Anh_`z$O28uA^8uty9 z)`#NuK8QE=z*Yezs=mwZgEwvl=~M`%z3^kBVA~+YRx@=B+5B$Zx@OwoOp?uK!cEOE zDf;W#04WYCsvN2293`xT`&abKSMZbSSGiM5Cq)dkwu;Rwh(AntwR=`TPDu${q=+4Y zP{egCjCP`j!c?rMO>2u5S%pVjRSYrR3)M4QPtee9DO3X#8O5Ip4qBHqw3l2=C!io- zt|!WV6>8m^ZF2M>nVkImVBO*Q@IeCp$OGL{^bMfEi7E#+@S^m@M&5>P6VUhapI_qh zCWiu!rnc_c^+3|l9`U4`_N8ns6chysxgchPvjcj#3zVlH-f z;MHxLyB`oT-5^n--!UwZXY}_&_}Aq2oOxUNjM6QC`~6p|Tx#rWvee^I^cW-p3SM}7 z_w^0jqt)w?JIam$7%u|7>eOV-;VB5JLHiT~&;|0^1Rb_c*gQ;>=$l(u;6`+oTV>bJ zM=LXI4N1yZT`@N2&YDAlz1GG?olX#$e!?@p08X9KH?Ef5!G3Gj7lMYy2c54gEFF%{Y|WCBD~(PQ_agOSY10(9$BTK7Q z!NtJ2Lz2rihJX5vbaYta#$Qk(&=E@%oEb=UpzA=9*+2~s)ZdR6(AS!7j2FR5THg@< ziJ;bc5_$&@59&k(fm9d(ArEz}qR4G64JvD5ik>bPet#$bYyl$#gDoK$1R4Wr!h^3~ zJ`WpNrw4jrs`d0?G#Yje#4TOs=F6~afMSSc$btfH2o@4Pp=U(-rT}21x>)Okc5vm^ zgV1ehy36I&jQ@&~7K)2LcFB`K7tq9q&e{30yrd+5H+ivQBhoAsK=Xl8I$GtoM-JcWj05a|TJw+-*L7J~0{yOLP6YIol1 z;J)0xk-s?bh8p?Y%86;~E~l?IKjQ4Ye{ZyCrTX%WXNtiq=5Cdw%SIu)g+>HzB1>H> zTk0Cj;K3dMoPV&_3<4`&N$TsRKtgXj7{O7tD>#e+fCn0+mKx_(6i6sn>j^uPy462+ z-#3pQu4bX_DD&DrM>Z>Wm_HZE9ew(3^eit0eOW8}=kUWIP)0(Jj$+~XDLv%k;y(QW zS7@RfPRRt28NL)0gi6sHk)`=R{QmjVC)g(3TZu`OlVF}gI;D^&FRK@Pn6mS}rRn%? z?M1@LZiI=A3G<$~ZgyLJjfT|7Ugc1qQO$kD+%Myo*?Ny$g>i-Jfs5BJBP z355v{Vyz2Ssc38j9M@u>(P?A4OKoTD?%hugmdJv-gZw6?ceQJkl>HFoxcX|Vj%Db- z=eK_c4bEkUjfdmWD!p{=wHRmKW&lyjg8))aRW)78+&N+6h_f)-AhWpgcI4$H4czks z2M2O`vRT2!s(ThO(H3))p9<1&{vI%E4AS{p;5c2JE?(DJpBuJ8e&>+M_qb ziFg*dD+~YX>3?wdH1(>Y;FV^$m*6-$YJ7b9DJjLo=Jh9s*94(+;r&Ls?FOG7c|4~c zUEN1TMtlQxtcof_q8#Vbry4&^*GM(-0hxr-(t!&fz^6b_ zA;`$!+r;yw^Hxf)PR&t%47CS9k6>ZM#mTAM8gJD}fs6Is;ZhJPzAnWXc&;GOp*;?F zp~>N0N2iqolEF?!={WoLzngkSZp`&wlVZmz@$NV@Ys_YmP+fyRGaXPpS&|V>D}Cgs z(u29Az7<*t03da66;mApRRbuqs5uHQ*4|+0LkoQ^tshpEr05h4VT~0!Umv*V$@>|w zk9f`op4cZR-8)&~YZ3+3A8+z{t(GzIDQY<;`2 z9k%XMmDX>_4S7_YI@xlbG3k!2CyIuK$^sfL*m-q&k0qkAPyB2Acbx*nluFWD;{l?p zs5U!y0^Cu8u!n1F761f(AWgWhX&D`ST~SsWa>nPL4OA%^nn%Ow` z$q59suXJt1?xjnp@)$GiW5=4pR|qRLc9gLmYQAPr&c>L(fqbO*x$l??#(H4z4geVX zC@G>+gteuM%MpqKL8|W+)k)=>0%mN~6X2(E-JeHXtaZ&3 z^%c%XH3=QB3)__wBQ%XU1yBPL-~~Yb6To7ihd|8hdajzXlhH!~0dq76^sQjR9DEvH zk1I@u2Rm-~u9L3+ImfaO53YEs>NXbY@l)yVZH&kt7>dgKP5YDBRcbfAmXpLfm=^IL z3#@>0V+fX<79OzQg6K?c@rl}p%y5N#REM%lDD94PG%yMNU0iydcf=ZQYxQBoRpWEi zX(YEOuP>~Jib)U4L_(7WJUU?5NeZNLgm)G`8%9qxt22ZR*Im4EMQ!bu-1m?`Sb&h? z0U`=ri=jcx=@KYEo-l_D?}qZO+Twynyh(Zy7ol_tg{ev9ba?K`kccWx>cHMg^3L9@ z^Giqu;lA}V`)>PbOBAD(LOD!8VEP0>EKQyN{+Tppz2GKG|E1S$An<)lBAY zTVe;%%8h^u1rkweqh0(|)z=%-w|pFW{d2#FDh7QuV57kwl*Y{rqV4@bM}VayUZH{4 z@;)S;-#WBigo`j3Bo`i=rJYZ~oj3m2Af}?>8r=0mG}+>J`Rh+RL$mhbB~!)3ywQwtbOEcDR)gMd&e^TD|=eR@C8%s zB9?L<-p!l)lQy?mNb(q8_4U;QwG4>RyPgfunr3b0>#H{{*t4gAgc-y*?s0SeCth0r zi3bRecqRdpB9`Op4>Fegcc7n{LYI%B2MIbfNU=$i_$l^{l)mFoN&T7+z0 zU5oW1z@gv5L%Dw+`5JKJ?fII-k`pZeCgq{9j zKjnC7ef;3BoEevuWg z@PYSB?n!x6NfGZgGeXtk%M;UmF4UB+F!3KW?>=_;-e%jaz_wl4OvYLlzu*6PNHkTIrQwH&{flWIce12z`Ecw|MSJl6FwgO4isKkAn& z4Jv#jvy@Ppd$8$E!b1S8;`9U89{u|%-Y5v~w{HgQ&$7Fh%p3vekHy`TC`I3j3jX05 z6l{YhBy2dfxO`YtBU|m@nWg*qFizZ=2Lp|3_CRfAcnP8Pt5fHTMrQM24TZlA^WUN9 zH?p!yQeo;wLA?^V%%>d$w!VIB#&~5}Jp-0Am^RH%(JMQaO&1%q3%0lY+_% zHYz2=8_!_Gc>cT^7+;)uDuh4>pzUDcBTs%LQn|Uij+wjSlMIy<%AZ9q4I2mIO7!Gs zA@KWw(g7t(a<02pm%k|f@cXi!*3kpA$Da)i%?P`#xZEU&#Z?dtgkf(P4J$RcBfpS* zI06YR82auA{zZccDmWGI6*$fnNKAx14)KR6>6V-G#p$8y!|;{sjl=ZCmh%B6rI9IvGFGdMsF>yTb%m{cWFf9hVuF*LREABh&(}Oc zjo}t)%RmiFX+(FRSt`qVs`#-U-_q!-Pq^xd70Ng{P1Y7%c7QD}Z)}|P z-_Qh55Ku$GKylec;FjAfzDHx4MNrs4ArE>}xNpe@Giz?LmIN`?;$-jAYN;g;{JP#= zN{3+)TXggyqO&(!HUTEVCP4Evi&<4A3%bdBv2G_V zX`BYq>>T1^p?gM^RUQ=5CSp;Ez z5fH-@yMsBDgR%VSGc)D6gEc;?2=tboZMUsBL`pr3WKlEbgfSng-$rTc=DAlWSW;K` z-cd?Nz@N=g5#z}(%I7*^cu=M@$03GYA-2GS~2aSSa3Ogg}21BDG_c*PE(aL1fD zARJr)q!u)=Z%jB71q;NlTdR1^B3&f?Y3L_0LVuQbLI~- z)x|s^?M6DaF2VLb`}e;nThifRDVp*#L*yAeLa+ncg}%3DM@^@}7A9|@wshKC%R(8# zOMVJr)764dg3tH8EIcvLlBfE6)^s)Kae`dkcYW=u8rnooVOdcY081Va+bwp4QHqO- zmwggrCN6)eH1LyzSZlvu)1vmTfUH1jD{^mX7YqDPC`3q96iuO;wou}mt(FBrDJB^t z;R_mGagGDUbjwmSpREa>Fc`eh)jR_Q_YS;FT@VL#c!cu8H5r1zjoiFYr%;I7L#9VLs=a^0744uLmaXmq!SAN zX*V8Cj{+ycme0_IC6SNo(=b;RxZIzjA`G4%0V>s=_m?;TH-g1m*FuIHQt72fq8s3f zK3|g*W|Gm@-)L;S`!xUH7%4KW^|s9VZKlkLLw4hfQ*fq2?JIb7zP~wH`VNFGU_~_@ zUO&jUtKU1jIaMh3w7z-drErJ+#klbAuBdksHi5VAUAra;T0L%_F$e?T0g|vfc%C5a zo}I7SKQni9410X+L~WZQ_SkXwbAt<0KahlBQG$01FY*;}(t{hfWy1%)b@4U+{CtRAZ zdQ?^&wq6ir0|yMOo*}nqg8qk|u8j7U2R#|3g#`O&%OEg zi?qptMOj?Q1Oy~p=JQ!uS*Zr!de9L0`O)1bSeo&m;crS%$hqRdU-+~>ew>*m0Ky&;?=+>L9+@N341D+3! zLos(@1a?vB2C32R9!thjw!r2&BCHji_58bfS4$VO-nWWPfxYrMe^9Hq`Di{F0bG#mh-|X+Sd1(uWj_pd&Za8GQx@Ors+iRL6u0f>{y<@e!uW!xBjJhu zO5K8YTuluGJNPPT*gT9OfL8|+Ft5ZwB=d^8j-%H$c8s?wjldyRzk9B1W=lVszB@*L z7uS;{wr%P6-zCh+t#Q@9C^o5-)YR3@sZgDo;qZJWjiUJaC_0b7>0}}=(t`SQ%}=S* z`g1z{A-9)ecw5M8Sr!uz}Sne?+GAz<`*#HeQ z|0O#+Kt7q5ytu7)UNV{PP74iA0{;>?=gu(rDA6)sMaM|ndNLtT=hE52QweDrh&SCSzbO%fa`ub@E z{7MRKC?W?uulg5%)KPRZ7{kC~5x~-LGT}GX>9A#GYYFR@QPbw}A6@UodcZrNN7Z7O zli6)p<1~;;Hu5rBe(b?Gvu&wHtQ0+pyYU@v4@*l+09%r`l)zHxlOU^ULlDi1;sV6FU@G;NAJ}bfO6aQ9K$W zPN!^#w^yHBS#4>msfOJrz`{}zD+|&(rpM64Qb9D^tCMTu@Z>n8cZa-6dPKKr*muTI zTYpVT#*HOE^LoYpXW80^R?xjcXe7oZ2K-n+;ss7J)Ifj|f&hfn%4-k{0`YTDLP6{a z3Atu*qi_#qiqT!|o{!fsGBwB&dP4Va8h@DB$Sx@%4Q)pSQ!JdX@Ii*oqzw*N!Ad29 zKBoH$R#86Es$=0{Q?~!@wLiv<9iXJbm=T@(REN?p7U0qVm(Wm-H`S z4=y-(S)l%>AjeO+Blnb*l)}#D-uutJP{6T=#W4AUV4BM696lK zg@ca^6cA{AgM&)?3kDk3QOO`PGqM2F0m@{~h$c~>(LBgp_@U`<+GB1q`bV9u{5b0) z2*vR(q8*FzyRKvKOyNE=exPF7)E2ZydzH!Bfjpl7DnP_(MdZFm#$^6l<8jbomS4J4 zc73JHEAaBbP{t7i4*(>C>I?Nnjg9txQZLq7g4+5dC>X;cf&T6Kx+dD?Mbp&-J)aZA zpFjCgpvjESN1MJG^9{!?2gF!~h2ppY7+`yiG7SK8YnbofJD1qEZn=8wD`#Y~70i0* zcq^!mrety?%iLDklKx4i6eq_fsVI%_B%(gr?(4d2~B-~<^~xDP>E(|!3*>NC8qp9{f4z5u#!{? zd?#$SCr?;Q*3Z3*&Kq?PD+xrd1^b+eqz%~>X~zv z_%hOfBOeAT-p5GMS1qzo!Q$kMz&ch-Q+xsq=I#zKR7Dvvu|$7t?5@x$aU$`uYl~sGEQ$+eVGo4@PZd@OeRWaRy@u z%|Oxb_GJeP|9x;TK;dBW-OrlihSr4kV{H>v=S_w1vS&y4>`quh@M#%Ym63BD)}e&0 z!+7JZGN<85G~Su#x${!i4Fj_b=4_^M)~*rlMyOh!RPXg$Ac~Rjza`z)FN$41K7)e< z?p*SnC%v5Ds7(>NK>P1a%zODfU}B@Y95G8kVVV7uIVAJ?9wxdzWs13?Y8<4?fn*j~ zZDx~MR=8<@`eWjCh21qw||z@4NzBBRat4}WY7Sv#g;C;ih`ZV^aE3kQ9=h* z;tqK^zVoy9D8frD@an+3;ZGSg^iy&0E#@0IXrVYyg;X z&oJfG%p3y1#&!B`e=s@Nxi9Tw;|6dmE&mXwk+0WiGQwdkQ18grv|QoTTF25AN}$Nu()LqDQZ?D7OIX6@FISF8_M zddh4*aj?N0s;sOJ7OZd#`5y211o|Eg`ow^Tp6J9qPKd63QEGvTXMtdqn(`%NTZbvD zvL&=ZzL4dsyE~0>oHYO=3C|LH|qv?Zzr^P~I3_x69q;LQ$ z;|r_S+0*fBDIwu^T8Qo|pW~6#{&i_)Q~v7=Gyw*TOsPhMF!W$kDp22C1BVn9`px_0 zQ_#tOuN4+XO_@Kas@?*Z)Y%@UKbk@5K*;_$o zKfWSbfA||Q?0R9~6h5K%=2rDg7{CHj1J5sSVDKZBfHw=SCm4(uJVTOf`5HEIV%Gk8 z>kF3=Oxr*;CI`}6D5D{=3+0^q^9KcSwc)ik$&QP!V2YzTz=xbcQTTV@Hiz*?*I#zm z!$ZdC_wxOvk2ro5cey*Puw~#@`pv0)Dm5lOwft*q{A29LR&sUeGn;~Xw{gP0lAQi4 zyF|M3Fp)g_sLR#=sL}5hsHmYY+**O$Mc_teC6_dF6XVIc`hEu65ts!cp1XyVcyC3# zUJA(hdlE90DN`6lnOJ`BI|#*%9UTFF6H^@#xgSrW2k%5HC<%h+wz&mlm{XJY4C@O- z%Ljfk<@@_}_-{RP03ErN{OWHPt|mfrE6;n4Ibt&g>NTG`6)sFjPPc449dh&njEvC$3?HVwU$0YSEYz#BjNl5`4+b^?>o&#fa|{ z+}tS}HK}Y)F@aP&I2oU;LML82l-YzH4sgLis;50%f_#9KOrV$EyVuL20_L$O)9WP@ z!DIRDItJ!>a9u#>Y{rg%$%erPvUWAhqa` zOp@Q{RtrlGE0(8~V%`C?4(619UF9c0u7sDC48Arfea*fbCL>DXbh3JFLGe1T$GQTz z6%y&_@8d&nJGabAt{pw`718~(LH$K3KvDFM-MI5&^AiNFhJU@AH+BM@`8UZp4Z3n1 zNZKzKZzUMZMrPE`WD1m>r7rmCYP*9Kc}e`4PZD{qBw10M0ROuxFTb-wtXr`k7~Ba zcW(def0X!4Nv=2ibDtCB%g_?!R8`%E$xhq4H~|CXr2&nA1@6+VX&y)zX@xuu7Uk<>cX$?ifF;*TX(48x9TLxavb*4r50*vU9#$jn1V} zRZ=O_)RfBMf>q-J{)NHS_{=R9a?*`TC%ciu z2oG^HLu`h@E)0WJ zkvWw&KO>UrZ2A4na1e!B(n*!#r}^I$!`sLxREgU#*O>KBZlLx$FNH6-VU_kjJiT{3 zmw)>{j*wN^Ss^PkTgcAdFMB0>@9;($*?aH3_ugB`-aCX4l2jrkNYlz+H&bMWDA0{#CS2D@7 z9bzLbX@Cvag{>{;>edPGzG};GJp<#H!a3mD0Jibq$|Q#`<76Z_sI-(5{7&gpuz{9? zj4Q#g^ewD#tm5+4=p=cz<~u5tRzTNbTifMWMfAWY2Nk$eyIg7y>pN1o3&$55#SJ8@*TCp-oiH&Q@IwMjIEdCNoYyzSC*q2#Q|ekAPnnH;?lR@xaq+v* z7Hxs)D}b_o7is<($XqkoX#;a}dVmFi8R8ZZaj@Y$dt?p&5@(X}rC+vy6 z`lcsF#QK3ZMPlyD7Pd@Di$+f3=CJd>%}L_J?*&o2minY3)Za5YIyxQ^%N%Z|w?O&+ zzxQmzWEBKjf~r8;aGfgcoa}63aPk4=l``d)sJ)87o+1hC2*Owngc&?4E$^Og zAKod^O@%Mlv4y^i9h?o!FK~%TDn;qKsm?Ax1?f3Fe_FcKa%0%hEz+Qt6Jj z-xx(s``MKfnI#Fe2b|g>BxvJjCY2~3*Z>U&l2$PLg^_m$G=#vQEc{(;RtmAWut-1Ce6Xy?=&gpm`ZW zW_SAat>E8FyDgp~v$}6BKiUL1&%oEO)de27AyOccB%5h6CTs%1KX%2xo{2p=d@Q7$ zJphwKzk7d+N)=Q_Ubax*R6TXXz_+l9#8DwlWT-ZXPdEIFyMjqC_6Q6*|1YBpuHdsJ z8$RJaZhI*0ZdsPQ^Z%}#8rk!}q~~V&*z-m+rvYM8d3X}g`;}N*q6-7q?E`H=K}zFQ zT)5PGH*j+A38Z&cpZ`MjaCLo?n@b%Ub{iE>_du$mg6n;TsOcFQ;jz7=h6=+DRv_SF z+kZ|j0oI1K1YS|m2xfzLh7y}d-Q;Y0o{XG5+TRkDA*0B|PnI_|@@YiKMKvGZRoR z*PYy;E17lt8}@R1Hzf+|@>Ehzl@bBIn(>Mn(tqdJAvg1>bi~a?SZIl3RL$;$><8Xj z*z756bs2Fbd`n_kQ{eXL{qN#n74$+-6d`6eCy9LbSA;Yg$lSnX-b9ZH7PESP_voHn z-U1Qs%RfI)3sV=DU|3b>hucHZj90JCKUtlMFBBqsp^-oSqK(`nx_Aws9h~{dLNZ)TUR;() zI>^F-u$mVyXpkP-kWf`xTkE7EcXDsNLhr-t0t#BSb(-r8QXP*9ZJ%L2)YqW^ronzQ z@N}>_tCC{b@eei^U%b%M^MaeB+F_EEa=r4>dYAa>wKL!Z_lRXO@X;j!wg2+&9oQs1 zg9-7g=WWj}nye|FmUY;=1m~rzE-=U>}rxs#8%# zE#sI-i^cxnpP%BQg*!1-!_AgaL#-HBMTpP(o8r{fj@-{+y=Uft9=KwwAgdyA-mYZT zG5{pE!PyCtQ&_g9?w8elC!G;_nV4qmlbD%_zv@t1?$EX@{xYifLO3n;8pi=~vh@Y= z6f#=DSqUsJ0|Qu!mlT=kiSYhjyz>99i<+MEoCnoxd1x4mY0s4ZEg2K zX__9CStRZr`hL$1p{pClKG6+EK37%#zv{p&uCSq@!A$;4uCP-neOKdS4=EYXt`lOB zoPk4Nc+c(h&u$!YX(Z=_L>i&>tYB6YD%jOvjJ}yUTN?n=V*AI=>iQ~MW|4*OU{j_H zrQfQF8&=yvfI;9_8CR0Y86Uqw7=ek;V}B3lW@VM`4Tz9IU<#&1PT|T^L0P?PYzfM1Qyg4^8oIj9%G5CUK-|*1ckPHo=I0)yYPDpSUy(Mt z#~{4|cM2e4kYP*6e}&FWAzhE6ID1E-e+3$Ca(a4xX(?oI8$_OFO{<_)1g}@Xk0RGH zR#=0yGv6s*mnbS(+aD@6k7?7A;enDwmzx)Cs}d3jzz`1^wLaz1l1<*!5aRUZmJ@we zRkHu6KVe}#id~}e4-y;E$&VkXlz123fAuUPa&hE{sE>_h(BV$>8AB{Ya=@Ng^xaBW zLV$xAtziJ{liSJJ?^%qMLgt;*3o!k%vam?sy1Dj8vSVA;Be5Ke>}r;+HXL&vC4IcN zPIsnT(9|HHOrAjlBD^8{IYG7VFco>53VOM4Lg48=Wu^rC{{m8oEVG{8`LzTTHfa5- zzHas9f&T~HzQ*_Rv&(CEO0X+)ao*N9g=GJ1QkHx3E@rC{jHthT-e^nO7e~}uTOUB+ z6c$oumfbTIL!Zci?bLP|&!8{?VeXEUO)FvR0(>A9oM9D|O5HnxSa8&;rA}>pbp8Z+ zu%m#?k^lg#)Z7XYstZaM!kWcFxV}5{N>YH+LP=j+drWRx8Pb?);uS-zmy$hKT2~o4 z7Oi5=w%^41>YWVrt3P~C&uMr%tt|8f(kVColX>!WVf{NUdxFj1PL#i}EB5!7CkVPB z;Cl~7^sAv4R~X{|PU6P)+>nVu$m{+#&1)|4g2xnA0f3HlbO7^!0xuCn=4WSo@GFGU zAW9VcYp^FLUw&b^mT1P2a+FN|o+u#F2)KV?;;S*yLBO zFIK#1_`muV_^cGfepTET1WP6`lm~EV$P5Z~Jd#cMxQXZH{?K>x5M-|*%gapv+HQ{X ze$Fe+5MliRJLw!0#KpWG@)IbWPo%7Rn^-Fjn^PCBTb4NfLedt@LP&=`pj4r9HgsB(00KcLrHGFiS!vGqGq6^}LcQiou*F(-Ul)Y8b>!rW#OTT~TaK-AY zogtbP|9UT*n;s>_2`~H7|i#~~u%;Fd4 zLOIhfNYTN{#o-GiVL;2F1QDE`T~lQBzs8iEefdXxZ4}lsnQS3K0W7cGj&z=oMrog_ z@Z5=n6`=YX&d2MQdzKsu|7~PxxEs1N+cswGO^>Tm>CD=Y6wY<(>3-EffZ{2n!}kRje1{`gBD$c z8g{g2KYR$DC}{`~jso=j^kF02iC5&SZ>!UFSK~_X2XQ559azUbmVAxCsoc=B;icyZ zLoIJz$-{Bs_(lUqhmAEzLu`X5HF)e z23$i5;IM-;<@2w!d1||}Y|?jj4eFenJ(6ePqC~n8ELLbDyF*+N-+t@f8+1oaMukTB z5W=8j_NJ(onNv3X{~v-pA{iS&Y!9gb5mz{h(3Qi`xbyoGKUhjYr^5M;iF+eE2M4I3 zJYWMtPK0`J+l5@;ai7qjqF&?sYS&0d z(;$EZeawOo1x8bt`f{dW!#?A-mDEtgpa|Bwg8(!#P+E@H+fJ4G&Xh!cyuBsctFv=s z`n_jxmvyH3IboU=Ex|O}N5A)8ayvwr?hypxF>TZy?M-U%UHG^m z!JQ=%E%zWHEiDXYk-~xkRDcoztjf1FaIWlxTlRgmjyk5B8BYd28HLo1i8u_<4mz05 z{1NS~sj>}O3g=saXgYTS%ykNvezEYaS_hV?j6FWCa7?o#$5VNRF9XWKLy}h+I%u*# zc@d%-zsxPQd~Gsi1*v2~ObA?C6j&4#HG*?EJ3LhzzDNjIfvW+gAlRFs3<(M0%9`@A zk%!tL>Vt-XAqFc!Q|;TKBrIEWjJO5feRhby_KzxMB?OxGluL$eT+%bVjy=2J@W(*N z6b4>WH&%vXx|>^w%+mT6B%WXm4GpF9THj?*kb?Q!?{a;su%(3r{>P+!(ws3x6V`%e zqsvbY$#k@<>Y2NO)dnp%xTNfGji_jL^1fucv#x|7E-_$F6@kd~mCen6RQf|$LUf-# z(@V#qNDvQQ>s0;nOD*Z)n<@_q3QFGh;K^0WFXb4`{2oCYF6dEt=X-Y(iKAmpy}>b8 zMmlyb{jN3>myt@GZi?-(h^#b;4C%*A9-J0G9Gz4}j(Jw*VN}~QW-_%0)zmbf7gL-B zsg_C5+SYUE?2BOa#5T#x>R##DSoQz_GT(YHoj!Q1Jcsz`P+Baku%v&yi42F=ZP7K_ z*{YAgOalm2aAGm#$>4&c^pN|Ha+EBSB#*${qDV$#xgV^9!T_HB#F^S^Dl??8u&_Bk zw^dD&UL1Qo!B;m-RFi@^t8RdvSv~fLAUY z#4uW{&dRy@c{Btutd4_TBeJp44TNMU3TAx56#e5VxR6TnA1r+8(2Nj`O-V~7ug?+) zCDksxD6?{PqP};ZT;iS}A&dskX`ApJ|Tr!2=m+ft}j7G2tpd8n4(N zEG1y5;d+M4W~H^GA&^zGY1LE#JBG#E><{IFseF@12?Ej!nL)OU&rKs}-Obz=j(j zQ$qZcszQNh$UM>V6DzY~C|T@)ffjBi{~=RSf;>7gh90|4&xVw)t}ZKQ%S*nPZ*%`ST~7ny9t4wc-YI))iTL6$9=3A+tA7uW9imxX2a_JIlvz-HI$g z;g=bJp zmc#<_x6UJj4?ahgT22YkFQ+)h|K%Fl&Apq=AXQcELkQ)n{TDPX%f!ky(eFwH0;8I^ zOQT&|w-Q!g5gz46h40Xt%`Giq^ljy}jJxv;*%U_oUVLVAu$C|A(GUg&2QKd2pA(!b zNoP$gtrU`qYLv4hbTWu!MFjEQNqgO%;6HUPGKYs%CxmsL=}&Q=W*bA|WpLKOxZHD!)>3tzoyz_5ig>*)g>^wc=>Z_`{x_hc+n$9^~@aBOC2$p&%YP;^#X3Z#@ zr0uq6;MLswf`o)5UFanfuoh>(wk2q@G_pR2zAd zsGenU>9mst_Te-a2B-=}-;#hc4TADtVg_l?J;_@Z%=mfU`PO$s zy11lWCKWKAJYd~1V6!^te5kOJQPA{3I$Su)(2Azv(}7`)0Gz;&DZ0z_WK_#DOBLmE zvfpbQ9`Es~z`jTc<7r-mQI5USoW;SrRalW7gg8~uc+07%#8B_>C(@eBPkH&-TPQqD z(=bmiv^6NP&HQ=sdL=eGx*KE(K^8LfpTa-VOT}vF8gW#7a)3nImZqj4R#sL3(Ze>J zZs&t7I3>_A{qXDKZFIyCc9AkoZ1OzI`amKhX@n?{8qy9S-oL-#qObYsE!kNilNH5m zG>Msuxbi=YdcloOcG&%d37;%4rU-*5Onz%Ks`OaB>X0`_*$09 z)}X-*19rA$D+9aa zGaQ+n2JVmH<>C;Ogb}oy^IOY>Cpty~Mre~jouAATr}V!*q7*)v@_1;1hfPWJ z?-otkyGs&5%N7h~gTC6@S+u5?x5iD$6+??tT(OOny@qqsj5fN@N%_ z@RJ5{Nn=-6)+ZVQH|ZY;I=RTgvpK$F{;VmsM52%goRH!8ycZ}k2p33m?fx-v8ZJxk zBK*AK+u7mLi(&l8xd64SQB;h=YFcL0rW{rs9d+hk>Lz6T`eL~(ePvR1$&!+2GPe|| zG_pf`yfDibcgib-5*c9K_NZ5;Ozpp7g@X=Kv>FS5pUL6Ojn2%dHL-H(sOs0~5R;Jf zZ@c98_0hok-U!49gn@Os5&R~|TM)ju__Q<_j^N_UB()n?cF7wLWSHQAtGl*ipMsc_ zR0^RDmIE8zJht7o7&E8Pp4}6&`wqVrT=>JVvkX-|DKel|5~Y#hAt&d(CadXSxaaf) zqx%aUCa0yD!#*=~(gUze10JTxLJx|>PkVbMzTz?nW_EV)El2K*z|||cAb%=0t`(`J z4ZFY3K>G}zsOH!ilYC+_&rwsE!8$|EV9fUg*15!Y5yNjK$nJ@{bAs_jnO?Jvn2qpr zj!d$j!c7LrY{>$>2hqXdVz;$FD|g5aUoniUf99&C17sO=k7gU4Dj-!N`mhmmIY}m# z$$lk3ekhbRyJB&yQW``C9%J?FRg}VZ_vwal(PPeviPVH^BIo5xc@!WNuK25Vr zET>NFC{hlziN=rKcY&b<**YY3f~Lo|S5&j&^O#XRS!h2vtifOMCNMCN*i@5?hX>qD zYOCZ7HWM0VvX<4g5X9h>04_Tm8SRc-=*@aHHg_Ja{qR7g7|-C11J`fjC2y6C z#9x$>gxqvxOYK`_Hv+~x(~azvRczoC6b1{_N4uUp8a(=gTNQjUIq912R@yeg&uk1L z{(W6-YH-_AOoqjpJp#*Ck-6dQgg;~>)vj61EAYq`%G7oN#kE5q2xJh%>l+)_FfBOI zRZ%>YL#KJ@hEDr6ZR;5#pDa`o1_{tjs zaU2ITY5i zY4x-T0K|iUH_mPGNw$4vB9Jw=v5_PDfzSLI%wxZ+7ygFZiq?Pie8tMpNdg=Ehd8mV zobk$=Vw;P>^Ya?lzOW#QqOt(H2awMd^Nrc5#o$*ep=^@63<7y<_4LAFJc0|}m&Wcz z1v5_J99CqMlFP3pU30h?fPnzjkk4l|dqXglw)MxK9D%EQaCW#{kpLMkt4z|sr6OHqJ0)C5X{5ep3zIya{h zv=RnU_)vxk806wDFUrR(I22zV)KwNqFCXoW3kAHM4WxX3`!;(Sm;hckOr4=Pmd^+Ech>A3k9ZBP}}7sB~iU{ zM}U8*2T?jCDgxuRXD}zRFh+`7;G*|m)?;>dX?=ZiMI|Lufh-S=oaiZE`_j=F5-rt6Rya5c3eq( z$Uk_fKu7KMk@UmsQ~n=5&-GtMHEPGHl<0rWAkI6~2yX7CljzFJU{F3hFt#dL`XiK~ zgvV_U`6gna9#V#5bX zyQ#|$He&3ODl360L*5&+3kyZURCifdJuQA*KxB;EsNMM-lN`HHGmT^L;I=xz0vdPKL5cA{5%NtoB<_7%_4lXX@`STcf+dyUaTsZmr z_kFW+FcNX|s9I^IKmD@#{kJ)o7s0Rrx`RQGxIwloI<4);gWs1P^rPTGhAgee$HxFA zbpxq|C&gR7Pi;J-ut5uIaxRk~lS_!&!F47^0p`ENZ8^VFL{zKE9$yq%sW|j53 zQ$Oa?18QSls63AxDzvc^js*@nz*2u{_e8yr8A3*T$gt4G)O0Y>z}~I#{^Pg7ZY}TWt5G{><*?PlouA#V8)#s4|L1 zH!>?^OenOfQ!X--+4EoNZr+YsxFe$=5J!TJ3d5=zg_D!hFwAVfD$5*1r+6l&i{_YX z+jnqg`C?)ypFoDw-L?%+N?^#KZ-#*n5=G#s6U2>p{9+)(GyA^T(|P0x{!9j&afmNZ zR6ngITJ!J3uWr&&-7P9EmUa$PH#SDrbmIH>pCvND&zmZ3xj zPC|=^)P7Jj?vYVWN^_NK3Qb_sKe2SS{rr*=47kJ6pZ@n4&KcM&!l%v6!xIQ`Ubyh1 z_#ArI{zxHE2vWeYU#{*4Gql*iKr|Ey=qg31SF}^)8DPLDeIj@ao9L65=y4R`49!crcj?gs)Wjzd0$X*6&?PuB44BdHIi?wl@Q;GQJH*w|cXB42Z@_=*b+|EpYu~+F&mLvNmsy%^ zTO-CdvIE`9$BTo!mA=z3@hf34s$PJ4pwOb7VXz)I`K8gF-+I2ugvY?IfFf=gQ}9L?Ls&KIylND153-+;TeRwPODO*RgpS z77q6?cUkGZcDqs*lFAO0W4X41-BE?$T@hk^SuQe&IIG#TRwkBlp?b0zu;hYvV8F*m zsHu^tO!b(V`7NwcZZ^SRE$XUwsz2{W8yOj?4qar}AZnj@huU2#!TjI<%`<&7+HRSw zatSRsqxN9WQVxVk@QyZT-<2ESA5c5MScDu1c46*}Xfn%09{LMV4hzCoA9!2UzrJwW zppZzld_KmLH3fGne6-+yKb$}>2c2V#9(yU9_VA{Qaov67YAGNqwcS6*o4LZyg^%^H z0|USf6vY_D+-omIe0$AamjSztdPlP<`GXpRTn1lup_|4j6*^0s9dC+f*{^G5gZN8=BYliQ<}Z~IOPVNh#}v|P zBDeK$J*;FbYeh5c2>88+D4yLSxceCk&9NWdrWAL%n+^s*HH^0w)Fw#;4D=b9m5qEPL#AF{WPr%OEtH8m!{sP4u%N1v#b9YtXl>YTIB5x_ z%?C8BKphKiVD^bhrlbfneNq^<>b`yGIITkQ8N-p_+WtUq+G4v|K=Zaf6Ei6y=Y{&m zEfqvEy{$=&HCYK(asW)m$k8YzCB=kH_MVXKaBx1eyb;=);gKFT)uKW|>PkGjTAZ1S3qJI;$j-;uI5+nOx%y}ZzcWg` z!zvGS{_g+%SH>SSMQx@Te>SfWx-5-YT(^b(aHI9DU5gZca5e7eWj}0<03sAN>@c|u#?CxCADPL&WNf5JcW{S5T2w9sQy5e4}naFUkn>>vPi6WqmJrc zL{4z#-2;m&L~=q8L3L)+!nHe#`1jpOaUzo0D$$tr6Tde550crEN)s#qWK5w1AbA7h zH><;=t6KGzuQo2Ri%vxDA(CN0VMBm?-B8m;+rohCiQ%+KtE+SO?Cd|9yJ27=j~i-g z(xA7fB_%)-Azci$`1LW&e|?YGmYb!ifnNFJl0=UJoYc){&n|zFTI!gIzdb#^fBuY! z$3nv=K`aBH*+bGODdMD_>E_V#e4BT-JMlkUKAqi1Q_p9zcxhqGd8BPi9;qQ%u%m_l z`7TQU0~%gbB029iCu``)aVUcVR%~=WAbkL>!jXt9{P?A+4s(zTS+Bfu)s)o5k`m{) zw&J?Jb>c#_%M)Nz3g>LrTvhg1Y2lG!#={AE-(r6sY1#-(CX^OBfMAfLH5e!%Er>-; zU(-njszwg8bua)Qj*61Xu8&;wg}HMhYsiblw{_RG@ntVu;mE*mr>h-zMeLN$0iZ2fsg@3IPJ8Qc2vqW%2d*Ee1CcsQsCmNFrnIS&M*5~rLjV4yM=;@f9%qRhp_sE$#@4E8y zFB*F{tx$?nk?c9d7D)$<0JYyAQ>Z&&D^F9%3?qyS)xEBb+%HqIsFi`+gHPZ7s=n>` zI5^cKx$CX>Yu6$ciTHqAZt_QAZ-UFEQoP>34q>jTl+ES5$2Ukz5s~k2f&ye(c<5mG zJ2NP9?;P7ULWiR6Lk!qQpb%ssnM7kL^V1)T$LH{m{n@_fAAWIqU~Xa}G1E8a=Gxrr zG-pGM6i&SO_wzpB^XxBrso-n_JpyGIE*YjIY?xaIL+?<+2G+~W6Wd}XrN6nrT)@c_ z0|zcxAio7N?Z|KGIr@%i8P5_YzB8?SD!o>t7k}}0J`ExjVGaR?Atlu?*>PI_TNc9@ zFRMJoDul>-eJ%)tAkL8fep7Ygdb=evBk#QdU@;Q4IfRLXI=BwrX(bmZnZMcbM(w-Y zAVNm5zX2+AoBuRC@ACAec}u2Wfh8nNBtK0cxi1k1GaAjo!9kxig0-YF z*^k7TCu0`$<{(Mkj(z$q0K`ZD1feK8Zxv)P2U>0CwqQwp#L{BKiERATzDe^Up!q=7 zj8*ln!sjToWY$}JQS+VN%q%PzG7DqzlcQLen18thD5L}lQBmNROabP{n6=}{s$x-f zHJ-1pul`ceWPQ+yci7+?P#nm7&mzUc{PoEqZsbT70ax4gy8Z&BXBe3wrAANB6Xl!hmnasDWEVgH;{mFns~`# z%ZcOcnuW~_e1|9sxTu+>KpgidVXV$?(>U$klFQNiCAhZR~Y`OH;w&#yCbO(l4qL>zd-7bJy` zetfE(G$wr_5@$XV+XFcW`*o;-DpsCoFdCI^D{}sfBaL#rgYpC=Wxng(yi3>f_wBAh zxw=GH=x0V`3W;xBvsF=y_IMLM8)Dj46A&NGbT%`yauI90+R013&_gd_I@Pw@=NOLG zqG{3-iGB0Nueq&-o&x(}Dn9C3+-)&$(f#S%J6(gQ3W-41VM^k^<-!Ac&(BW`Xf;6X zkh=h%uS-g`+iZwBTmu0>dIxq+K|mF-8@1!Z0x>i*$hPeK>uL~NopS3?d3kvN7zHyE zOL36}S5_hcU=TLI>;viF5{Tr@SIW2(wo}?du?s{R0EnP`EC{0>08apfjt(Y*m>Uok zfH-=-aAfhiJPvey9F?`tBhvC)?JJ7-KRsv(#X$z#H}veDFOIhM9!raS22V%2ljQDK zvF|}7Oe;V0NjWmZ#BVPC`*T*-hgP>zao|Qi^3NjJmPgyIGJGhp#soQ*X=!N%Sgux& zEgSILSQWN#$Bm{Zi*8cJAo~=^gNIHC98DJ&-}$Ycwrrf7{=MMIA_DA?%Q4=v z1H?i%Vc?MuCf>Fkws*sbMq>H5VQ$xJu_J-q0I%GYI?STE^39%{7K82F9xD1S%7jh2 zhZUrZ==t=_MZVH+Mo-mc2)fajnJ8^iF*vcp0poDCACY*$DLW{Ff|+NW|FN`+^r2o8 z7LVw+c>4xDcfxmEcyJOF6&1OJg(KCOi=X0J?|-#0{Ln(J3WOkJ{z=2O1of-0+`yu2 z!{Ly8_Usl=CH-7@&>nzz{;ZM*P&`;hYi?@;l@T016Hxap*{CG@Qz3m<_}!6hPsSGAP6V0)>od%Y@UulZ25W4v?Z{<^Z8&^PPi9;emD zA=m&7WsbDgF5tg7n%-zXxhAL`<2iVI2Y?cOd#AUcm?yb{73*i_ z&!cqaE0!l_9D{+qCR92_IsCeH68(7crDm!noDb*#Z9@|}2Yi2i8uJCLdyPJ_@GCv9 zP`^;#9>c>|opm3|?=8%@5|jS@FH3pfv$OHNWOkNk zkJFU$zRJdam+U?!QBRecRWB%)psg(A&!-QJpz?Ok6^2%5Fzg;OfEMlu z{V_x>#+zM1aK=SJ(W%yZGx4|!4=#Y&s#6fXz~lu05#X=zW*8KZQW?0efBnz{0mAGo zJ~S&{xwlmoydcT|uKxzpLCnca{{K}p;N&0-x3jCO0pyDgTfGk+sbDwD7B|5Ikn3h%p0yxtmt&ncO_I@T8^B0|8o91h0w52-ry{jxR1Q>MSWA z!5yI2q%D@%{n{ab|gE-jPZ9Cu+MZ?Qyzw7f{% zK&DW6hW72)g9eY&(&CPX%n~UC_fZ0dgOrs2yxY5*?4ud^Mi}jlezb4yQ+z826Afb? zk(nYGao8sY>{`C~&Vm{iIU0gXP``tKHUIDgbUug8 z#d3*O;T4Sipkg-%U*q<#jS~_Je8`1)_=&wlVj*4b0dgA&E)OV-prpB-H3iC+XfWDG zwq(GfhE-OAZ-Gz7Pc7ECQnUAI3f0qm_dof?WG;8HSL`5WSywFd!HDABBQe+ey(cl8 z{oD1=5R2~Xq16W}PEveAwwclLi2DJ|Jv4zO`|ox5N9>ty57xi$y?$==--al(n#wFs zcJDYpqNK5YnuZZ1Ihid)1bh23l9F%W06jEt{9s$!keQk6{g`6VX3e)IQVVy58?Q)1 zA-}Aw>?K$=zM!U{@X4x{3Z_zt`m1=Cqo2GM{YBh}xmqa`tG1y$Gpj9M8)OQ?DE%d3 z#Ne)E?Q|k~QUCRQLU+otnS06_q$uOOaPsuSJCnH5)jEqK zke)DT)&Q$2xMga2p{owSGl~K|4ZQQovZ3=f%$mFc4)0M?Elu0jn=)nhJ2Pj#dZg%+ zr#VVaY7g=8|Fm#eDk$#NRBA1OOAZfe+F~Ps+5pH!~S@gA5e=7=L5)_vgDbt}nibV~K)mj(dOqwf)R!9!r8qzs0tgDuMZp+Mx zIUX-Dao4TH+@Tc6udKv@V+UCO{AIkY?-;0@W#we&M7RQX6Qr1>h#T>eXFBj?N-UAH zxHKIZ1(h@?s`#j6rQ}u9wi3j$@-)@ z3aO=4)rMX3eb?t%>RO+W_7x{bFK#&P>?(ouu(x?6RZ<~FoKh=oc}_ZUF8H!vO*UY} zFe>_H>rb|8Ukn>BQPz?w-gENHJGlzpisE7iZkB%gzb!kRD8FYZvx5Lg_3Qe7SpHYL zFVuB(QUx%16r5W}I);(m43NLIegAv_1%klb&tppzC)|YjldKaCLNXc0Qh>xEX_~SH z?55S~Qbp^E?d|PZAPsKLK`J~Gub*kM=3zvrlePcg??c=wTOj7eK>#N{Gs#(CO98df z>*Jf-E*l;zB`mCCpA1Rh;+2b~LLI@zCqmQ{bD8UielX_rdNcCF1s_IXvd>3@dV+Wg zX7%}tp>@wyOie?uNipNK2Q`u#@VUsOKDggH_i{o}Ys%Mn2fIxLZEd}S2q*zS+wgHhSwyPmkbB2oUV6HV z&HF7N7C<6IAV}2JO{12|V*mO?Kk>{$Hhxw9V@7f@Z^(yX5Sd*_X@Yd;7RuGGxF5}v zt=Amj+jVleb%Pxgg!;jKq2(F=fM%hU}r{f8U)R*g!Talp(KNj|`64T|ovy?eI1;5FV; zFGC8KKWeuf*eL{n3q@bq8@!$xObg%-7|Yi9#AJH>V1`S-~Uw%hKCICuzlWe1c9Yjc6X@zTRNJM zh|CDTm#FEBxYasUxwN$@1ee!-K>C8K%0qmtV*bv_mUN0oUnOW!a>0@Wff_Z$V`?_b z^slgx4vqWhXNkYsxB8sS^NSAbWFJy7bs}dz zmHwk&wA68?yTcrSjwL0IjD{yM|AWv=#Vzs`BJFmAM`5!1S#~aKIQYQHdE0%E-%P5lXB5WkO;zU3;Vc+CR=*6@g0tsL*zc_9CV1;by6fwi?CLtvC(x@R8&Z%?X6Q)O z9T3{S8!2a{ys^Gwhik18QNwA#K=@|i5ae1KsOo?{o*gc5K%m1bLBfdcXQk%I!SpdX zR^SgEcG6dq+b*xi-ls$G=cj{9u;3R!639xa>@cg}9&!Df@)4vpaAsx!tOTpUY%yP8 z5^j+xWl;NFZNB1m-V{l$DC-~23oa&pQ@Hr`*HeSL*p}>xtwB1f1!8`9MX@DI#;4bny$oUVcBm?0Jh$@b8?gO3% z5QmL}gS5T9eI|=#ZLdW~W?*gwjluqoTj^ENSh!}ZQL%%?qL(=D6(JVh_R}qIGO$I* z=E4Kk2UQYZbL=}YS?F-JeoH!c5e^tTyv=fUl13ojP$!Pb>bYI#x@vH%7W4h&67tR@ zqnl94bz5aDw_P`7kUT`U`+2=0l;H)|^3BZ5-H2;1u z{QD7BwtY(S){GmhQQZ=(YNT(>X)eit*c;OyJ4%cbGF0PbBdEEIssM!iBly;cK7jsHH2jCH-p0big22YzPe95o|pYK=13v6{?;?ikJ2PzucW&- zhzI4RCEj=8Gj-7~t=nSte=PsznCxgOZaCT)4UZ5xOH0FykG!Bk#=rY6g2*Su$f{_4 zEIF&`f%(DD-rt5Hsovc&m+JWF;A8-c(*>QKSX+OW)3!lcha-a@BdaO8^Ru6e9RLEe z2El=CtW9t0`%WE}{QEP`@;-(tQqt3*f+{iWDx|$x6yBL4ELr2~jc!R34(pD1F)>L6 zA3oU_^`jaXsBXie@eo^GHOS8x|Ng}U6bB86toigZkc2UV(qT8#z83I^ASZ3p$$RtE zl!iez3d^#E$r&y+8wcLh8yg!wAr+w}#_* zPT93_4ttBnc6fEDV}2H#y?^L{%#H&36%Y+`5LzHrj-bMU=^9yC*p0if7#T}CD~mG* z8Y%J3wSe`H{HPsV#(pX{=z?%Wu){pyH&a$qqt_C+v zU&WN<>6J3Jd1DyJZ|X?s{!ezs|BHMP5cf7P>~^LR^*Q@3NI9Z}_P=t^6RggB^&ga2 z%JLKKP&62-K<|12!gjFbzy#rupvM|%#G@5ESo!lI>dX=oG_;MjbwC8>>DfnbmhrQ zCY)8HGSKhAB_9eDK4fD`5f5SKawLV!mMWcesM}e3s!}b1k&~&t5W-eT=fU8%$$p0HthEUd`by6`!Ttkytz@l+*`7*rqjtp5yuMO zJ5p7CWqxh5e57gHCvtR>@kdm4hYxWwCc`&>lcx~QlUF3UKrH;U>&K!d=Z>1c4>g3r zmRDB~bbCjs8yJLMy%vYr^Os_i(TFbF+>74VLLi|49P!MEuZYkNuY~;NVYHC!>Uo4Zek0q7{1ZQ>agc_c3<8$5--<2kCQMVtLyE&J2=?Cctjjt zSlpLq%DlL!RZw%x7fUS)SUXR4{ldggZIaHXp8H3Mb=n%=)-#+|6*GA~_g@~~-N3O} z^-B7MfAU9V(Ydi&H1({Nd-p&(@$D>M3RPEUVqr?df__eIOx@IRaSj7ZA+y;;>VrSy zx_$woukPme_F@8}HbA0l6moTi1`-c)UaOB#H%4Y>)u+{sLEI;UK;AtK?uYZmnxf5i zS~`6J+^v^fYeqJ~V}efnE%Nlr@D!2zR}2c!!B;}N1A{gkCgg3JmG;8#!cHn0D;(6K zZ)Eu>uE8_!A9iLbZp%2~F&Glr8r@NRZVRatNYicPJeyU=M2HPp)9_w@OBSJUsk@Gg z-MZLe)hlsSub`Xd!`~(OdWhe!-Hw9L*=|6D|KRg6Bb6TcTYyDH7K$;LIm{p2)Q&#t zo|hY`!JBdw!&@O`&9jsBc;!n)xuoXhR3=>^+#2X0XyHLZiuSb~m}$>j(Q|UjT(7*? zvQ=-Z<~qoM?U7UGp+OEAO2F!*RHAY`1NrH}%n)3BKrCVZJoWYQQqcsX+5Y*7&5G!Q zMmE*MrT?_XgLz;~Xcb2>7i8~gkv|upO==++t0A>yGK#B`!y7a)F~NubUnXO3%Lihx zP%cR<(|!336>eySbAEJS%JH$#xda8%`KwD)KErd{Lv9d&WLwoOT1=V(n1(cu)MQ-uPQxN~gVS%y23>9mIDAr4wCq$F#7?Db-GvmpU zpS@IwotZ_E;Z}!je?{A(=6wV2G3pUq8NW^ErA$}Dm^@w}JDM_v%;T;(!6?=E738&2 zJD?BNo2*)}W!#+l|08X(TKc>R+Zs}-jPJ}`-|b>Iw|Ic0;p4Y1=UXbg>D9ZhTNAGp zTFE*F>{pH6y<`bJWU$UIw$MZy8I&hdKDDuEZx)~j zFmK<2^bE?%D(j-cLd8dNND2kcHmI!@MiV>{AmOX+{cDE=_jIcGV~A~wA2o@H8>%L_ zD%-@hur9+Lq)rU#Xl$qep{B?l5a35$@ZGz*gR)`q>yJqwUoIoxcD$q3nb0zD2BzchItXZ*ENxxKB(K*&-^ISf`3SdoQL ze{ud?Gomae+w;V%7_S4)>r(muHTCB4RPOEf_$HMx^O)H-CM1Mp$~I-%*rv)*#?qiV zicC>tn=(YGWQ(#Jl%YW(NkS#5Gzm%4gd{V+b$8D9^ZcII`Qv%LP965W@Avgy*SgkP z*R%>3&7R5q*J{864l=Q4_r{$&@5oK6^z^(Hvs_aBEI*Vzxz%&`z+!u-QQ>XPs?~FX zg$)j+#g{Epl@gyk-_)~zNIGEFIMEN(St3X}>Gr%{q&}!0$Y;u3?%dG7?>VCX)%_o673d&C14O97J~l*4i#vL5*|Gx1I4Jx0A7j*9W~4IWpqlCeGYvj0NB>~n zg|vr|U+lg+W=SF(i5rfPRXwK>!H-$~%*^t=Q_sxK%}eR4bJ|64@!h-?Ry{~2dy`5g zI9YaG%q!!$dtADEg%ZcsGn#{+?bx;(=A2FmE4{dDT}v22l?OgOolH0nAOmaxk`~-@ z_(u(~O9_N@0P47%(%Se&ez;b*-kSdWO_p7rY~w(iROI2JtjX_as^nHvYja+fu*2d0 zy6Lczr!%K@)GUVmE|)W*ln88}i~VU^y=6MERZ9epxl}~1f;J3=wGupP;*&tkEwwng zHeKJ_9{`V>72E_LB8H^U$}I=2SnH`kf`1MVdezlitP>NhZpIRF+5&}-E9Y8WhPdMnBkVd_?4DocHayJ}u(%n&028=~@ooJX&$mTCEV2T` zA%~oLb+i81o2noMBuk5Ne|@r}hV2<+*bz1mBwlxx=wpcd%EjrTMGn%TujLnrk;?9#!q*Lp z8}ua|oPi}uh(Lcko-wE}i-A?XZ31qHe9y|ES@`D&U)M+yq^ zeZ`i6NVtb&Z}j?@ICTAbRn2)_aZ@hD&}=vs5E)OB+HcH1w5_pAXnCw1lN&H05S`MD z_xoy@gt`lctRO{9dT;LObz~X!uaW)q#d(>{Bc)R!7A2jF@B;8Y)7fg6A9!Qca6{iI0deCSkC%oI2iTI*E9Rb%As$>%;y0*sqC zmpAs2F1xLK94P1=6CouXH7bas_Iy*Ly^>qS2iuO!g5a1_(eY0$kG`;Z>+he%*zb~( z^*}az%FdPk^z>$(HDg{1av`{t z(szwc{{orc^@0JHEC!hnj5q!WhibaV=kaS!a@AtKUSR6i6W4oE-3}qu4E-6tnCDqn zLkiFmSiQrEZZI-5tj&L%%VuF9-_~ix8GdJ;zo=vKPI;;-tZpDFG^6^tJm6o1ivmy> zvI8a)28*N>Qt>Ku{2!pO<3}z1bT>O2P?$$X&x>djByuVWo0rshyj}iz%I@mi0nz__5{x|-m*@v2#ofVFWiUN8y3L^ zv@G1%8It^iFsUXTGFmv*vwQJq^ES_a%0?w9RMd(lyyb+ufllXSk0+%M0IX(BV={vs zd%T1OV4J6h`i-$;Cm302l;9Ev5~Se(c@WIBRn1!-tjtI~wq~Pepl0-%+%|n*br&MXVd~^OHkdje2{n z+IbaQX0ODRypf= zUUu&JfgSA1dm?Xg*j})j+4xm{mDP|ru7%>ql)IJu3MEhO9}wTf8BZeJ!s6l1XU|Ax zd?@xuA@l~B-4BX&3F+?KuXbPw5O#%CAE*E}GT#l8ZW&9>ENSM6+ zZk>Bam0r17J@=%b+j(_-9D*q)hysiq5u(Z+JJVG}Oq}ZIiFz|4ig}V3A7+$tn^Ui1 z?qIFII&bZt{1@l8j69)vpDCBHPuh1r8mflATlxz>dSjA7lM6Qb^8KClsu9{hxPV}U zL*I>#C(c2d&ETwffR*I0SG(Nr`kz{{PXqo0h#dcugA3FNS^%0bHrFgz)j&)IB~z+ zc=w|yP^@guu3tCNkC@C71IFvu`A6=KuOK2Cyu1o-+^0sSXL9O_I~A&IqGo5Oj5|hY z*|2JzEbFr?_3;W+?C~EtbJ_j%fn%?5TqkC`x9sNuO;K|56lVDkH=u_$kBBgU5PvTw z1s@U9Ff|mr5Jcc#9v+@AKYzk8ey4BmwR0iou3aNJZkUk&`Yi~)mD?xCimS}DcmJ8% zx!lFd3o%7F#Nh*|cNngKmA{FY{fh?m$ zbAHJUZ|RMVP}4-pwsT-fLG_KZsAZk4E8=o)2TEc)n?*o?BFwM=L-CF0K1e?RKKwRO z=5_v2D(T0L{SfjcP|*l0gv49N{+mrVY*sDk=hKn|lOJeka|u8+WO{-H z%ORWkM;)V$dl#F8=0vZ!t-}38#EN8PWqm(y=JQ&$sZyVV+FC4cpEt98%f<5QT`nEL z{CmrkF5b58bUl1kyw&CEABEe$viD_Pz_17T6IX8G_=dqL4;LZEM<}>dAr_KGo*<0X z=5U~Ja&lffG`4N-N$(s_%vg#~AGqID(h;Bd)wf12g+G*!{dZj14<{PuiX>rV{<5~U z)u-Pz^4ZaOmhNRS82r1yA@zB3#|yR2=Q560Jiq%JSX!FvIHY<&-R#>{CUx9$`zhT^ z%S2K_M$-;~%4{n3e{q6|b^C}?UrDu48@ zaIava2`vQ^ndTJIkNvw73vm)Q&-Z2MP*jCDiIJtUhgbVK$SyE^T=0WZ$%Le38E8t- zQSAFLWLjKv@^th@db?9L%_aXyAh7w`tSpX{VzZ6UUYs9xOWBv1xaDMk3-!v=vV(8m zAfdyS8n|uJ|L2>53K#Sdbc_L|i9H~M0s%S2ASo40Ok~EU4&_ba3>7aVt&a*jA zHKaK7QnK9{_GC-f+`TJxlZ&_i6qpa?q?Q?$(mw0zN}-gcjn0l^72{IbH%aQy=a&x) zMIN?-dKZKIR|!MMT&EYNVv1Evg#xfi8gj?wRe?{QOAXaX2LU-^5DQR3XT%LnyIvBl z@{XyXm4p56Ia7upKsgC%04NbVOG=v|{>U5Pn=^X8I=kU8QE8EQb-#b_7vbPmNwZMPk@?J=#F(^hP zB;=ce`;IVFPWp-2BJIgw-=_&=(nU*|F37Lwc8h` z6QiSQQ|qBP>7ua1)qz#_Wv|xOhLKQXWtVd8Uv>j~ehd$@kS=@INx-vEG&15tdB^J3E$YVu*3)J9*e zdN>a%)~#E&nE7}wn~d8EGv>=OahZu7HFoUrd+)(G@7Ptn?&Yc6w$g2OmfD(@BUM}8 zY3EC1|F~UFc5*!V%x+@8(&1fzLeR%yt>0+}_kva*Y;PfWFpP?Z2z-Nq>dgV-wd)#w zfIsGNTK|aD`tW;$`>@-U1&U=n(PKzKqEMEC?g1nLRf|QCzjuGOiAOS>Iulp)*EvVta^lO5f^Yzaj+Od<~k!mtFH#@h@ty3tf$!qodA zjLEf3km!c|B58=FvkgU5^>H?zpqQm^_3ka4I))R9rp+GG~>vM<7br=kcOI)%E_y1 z^Za){k5pGHO>fK`I*>PFqG%%kGmk4CZ$TNvmlNA}ymy26AE1z% zoBK=jDAeXqnP;Dh!h=Kuj99QI_;nKX(nu=&1LKL`X&$?yHYJF=A&oR}Eq}So6R$RQO za;z6Cv7Mpi6Sr|vT2tV`DBAR+)tgathdWk2xsArqv=IPVd3=7Bcl*OsTY#kv--S7k z0c5EDp3Eq&tK)$ZAmK@%8MX?P{VFZ9=GRX@tdMCPwTTAr;Ir=T$?B&5Td#)3qt6aS z05G|xh`23E^A!BTB1u{H`$vC)+`xmwt}vSyFJ9am8Xs1iK`E31`!w}ybaZr?cH!UK zNh=M0pV&RuJ+3bIZ6v3KbgbK#c_#F>ql=?R!-4U~xPSB|A7UqW|JWfUN-ibg%R)H# zeImgN$DR-cu5!DK@slu4B!qKL7}=vGg}n&@Z~_?4Y5;#GU@VKAGFkj1#*Ov3aL9p9 zxZvgBgmLc@5<>s5GZ{KkOzjALCqOg7(u%D1Itm=X-=61ltlN9#QT0uR!-)5MxOva6 z#@@LnJ-%XkFQXS8*HZ*%i|u2RV>CYMToqBAKL#x#CymHOT9O-Zp!rHwmFSf#8!&}$ zJhEi=8U(#l^Gg%87;f*&&2t0r`dX-q%$BLpGXkW0vFUVid)1q(m0njSu6x)aVn?XG z5`|e%@=DED-R%(#OeQKW0`mYoPp#R$46f(@cwsD(973`GwTm?GFQPD|a^#bw{aWj% z)Nm9a)LghPeNNI?^*fF}y7fB1(e7-)_KDj}OVN$uTuDt}t%&O;$aq|wxUY~GfENq{ zC$n91hcy=tlT4K0aXdvBCI72DP>a(26z1d|iU{^-QFoAM^T zN%8S_T^)FjS(E8aNsi~P>>};jC3R?eFi%TI$kf~0`=LIg`n|lZP;(t-ZQh=_J{@7+ zipW#@IX-P%%2ZRZ$vPYBf8dVZPu|tThSC||(uY9SpW1Nvh9O{Mo4+;{r*u2<^4>=$ z7Q-rQ8>kh(h3KE2Z%*rrmxE0JLBM*Xpzn9|dMp|bwZF<5m{)PkV|eM{`b1MW(C)LK zO+a!&lnmE-1*mGolD>=<>BHQa*6L}d5I+}VN*g$jbV=E8l~SjioEc=_nhJ62&|T}{GAKBOUuoJFrt3hTlz zZh=dRnMI~%k>!Bl^(E4-ItvB#`nRkXe^ujFOh_*tmwPfY}}$V-v4z2Vl;`#WTm zf`7>DuAdH!`juVuKDSl%mOu-(EYXjTdznjgT`(!fq3vqzSGB0gJH5>Td0P`f zSrZclz>jO!w1n#oj`{9o!_Ho~$}Q1UifC+MuX+>z>Xq9?CU=2@n>!CTcYTTA^(ABGz!C?pLONQsz_~ymn`*w*$pt$>VoHhROm*oX*JsY0hKehw47i z0;_I&@v#Bj(gQqu`VC#o;7kTkg0^>Sbud571{Z^M)OPjO&llmN{-KbT_}9u$sjPy_ zl7HU;GdY{*)T%dkANgxPc^L6%gQ3gLv{q)j#>8B4IiCXJ6|r1l;IF6^W33KG5}qc0hFlek_Pce z7LGc4@(4ldv?_{O0tVrTHJSlClb?a)RH9k+}+pn8q-_R)zT1K&8M{>-}(9RwF z2^R59xvSTsdac298_8;4OUE1g*#C^|!L}{Ld9A0{?DRR7%bT;tlIEGK>Y3XZ_Fe|- zw=W1&3?g%reERiw@A3Bj(EChhS6ADtuE6G=clLEB(!yOT)@p<=!3OXv$eIg zXW7o3$fw5<^AUD~+EKRhHxSr~#6{GyJ9}MJS6t=3B(Y;??TMr0a%?br(A}``4*>^>+Z9Vf3G*F#e|x08!T^G5Poy})v+_NB<>wBc zxL?2a5yvH7*0(iF5$+oxXi|Km+?gok&FQSW`LVKHhTbPPw@W|#@{%)W=HXc60w^5G%vEQ2fYt_wn^DqFp)4Fz@t-3Khbq#JQ z-`@IY$k!u#)t}VNFfU!bPrQ6x_Un$6g#a&;us*7em|79$Qc(O&^OL<9M1;r4;=;&v zMB9LxfjZ@%Z*ExI=2{++)$!{t2@08ZZ8T5NE)okT=yXW=SYRY9M8k!AUqYtsM57(M zf8U&F`@sj}5+v#nqDijD%tsQO1ZMk5>Z^`7e*_x9PCWH?1~!4h9eT7Q<_~t&C@s10 z)N;r3!iK={bp-`ox=PiYHi>O)P%OlN2xWzVZtv~Wq^zr5c%9QFLz?@1#fWSGd={3Z zCf#C92@)-fjCh?REHO*0ANN#22WAkh1+1*g+cPf7JlJuD?g%e4_t<47P=>yk%8(C3yF?A&> zFM&0#-2A|a(g7pY_8)I+kZ**4K!ro)i39DZo1F%Sq!e+~`}$--UxAFguwKuqgo+mB z+e-%&E={h<*?C~+7w_nVECch!b1H6WPzOn18FhzO_J<$di{&hkj`ffB z%CV zonkVBcYb?Nym8l;pVC-boiz^!T)wK7GIyW{h(0+qJ;ExMe>IFR*&=*8 zs{W2=?vu5(L9j~KV9gC&t58IEETRYau#)rG2gNGl7K83&Z?Y-vB^FOy|Lc;Dn-q6z zf5rEwERK<3mNdKy7UV23Miqhd>;Gwdq7)4z5Dt%!A*)7WhPhNUBDk6^B(` ze}$BHk08Sv#YECLN^DQvgve=!gUp)+$1$e^eIT280_?z1`2RiB^_+y#5Sl(W?AYP= zFjWnm7y!}QL!$N{L|4zwDn*K};pXvlySAs-?E9Pje8R$|d+%h^0&x#@26MNhpLuZ4 zlwC^d%t*ep=iK(46%VN&-BS73l-d4X<;>lNx$60@`!sz!e_;^Bv%Qd0+UQu0MM) zBgZ|KP=P!bgyqFCRLY;_#bXa4F=06bZsPAcT$iF5$cY=dH1Ea{y8ZH!JaTw;FOYkW_A`X?YLh}UcLVSe`1kFcd48ma3+Re3hKOJt)J zc2Ufo8k$~w5V5-n#N#+uL+@fVa@>+F_%d47t>ER2-NbiPNqd~nZs3>(6>Mu6e4t-0 zAV^$LMfSbjSK=%W+mpIUd(W#843ujK^ozi_#hJMo3wcQ4zn7PTvL6U$-W9 zAr!IctaOIMn_T%&Z-h&?^lo#fPOdMsE zpnbr(^r-abAP5@5wAqi2~w)x?-ivD^$HOKAfTR$u;YFQ!rs6h9?V2x`gL&iF$inS++xWUEMr_ zKU@0x#6Y*DuiktE{e0uVnBA?5xn!GfDSy_d51=L5Tl^5mA!`5r@eQ^D8~ty{5vfFd zOJMK&C4>39ac;oMG70Z4k*UzD-E7v1Yu=50DaqJ|G1{$PZL7k1qbG}NYJ_o)yWUv> zxA?te(rzuxe7lbH8QhCj2Oa8h!Z6*8+Y>WhNQy%lta~4e-V|jRAcYvVU&lMO1*$Z7 z2T3HNK;{RXZ9M7joeZrpuJ$iV={75+-ddmNA0OO4@pUEf3IZdIA}B@(7F`Tc;0H(G zgKBE}GGA;R;7;#<>E3%kuVK#fb?7UO+kx3hos~T@d!D|16)v&)#`n0M-7VkWtj(-m zajsYe5nAh?eK0=0uwWMY?#~J!JSUGY>s%S7<&+%t_Kidh%OcNDL`e>*ZgJvUYsDJB zpA;fvzPGcOxx+s+^!tc2S9^{}`kE-qYKZJ=)~hBHX$ESxK9?hDGEown5*fNP8>zJ`Lf7n)Q8zugegZ_{mlag zxiQs$apUmV^Gy{5`Ds6@_k8A#y+~lYYc9l%9pkU>Ml64I<=xTBN`ag_(Iw~b9QnD^ zKlU8tEh#VOLRZw7?YO|PeS0gP@3K61MH_~{CqzUQ$XXO0N`d~04~*NW92_MT`y?k* zZ``x9q-&p4i2sgq4GcOpKN6eqq;TE#y?dQTLiEsC1HuRsStxto?Yh~xqlUParzR?5 z(~@Lj#5#;;)d?9bBEz?CS*#OXj*Kx9t;=baCe#L5>QQhDGd9RRex z1BTpcGQN+0uw*R|Tf@P+;J{^(j|ABJz6tXyEDHe(;_CJaypswY>jIpO{=Du&Q+A~F zfrC>@>ebizftdpjR6QBJ@7`q)+aNY&%oMGKxVfyvv^~z!x=Y3UPcMH>PVbfi+$x%kCwle)_)U zWw3>=Vbe=qdm?>&5>h9E4F_3VeD|&-SS)a5#1(}kZiqF;2+R*yNg@%m@y=k^bqCqv zpt*qN;m)mZSMTg?;#miR98w=qu=o_f1TQbIYw!qT;P&F6%Q+RL_UjTAc1wsABnWva z1~egbE%>F`%$_BuT2@<7<2v$^7>s?~+y~&-_4W7XhH~Gq{!fi21P`Atd$+r#mC-tM z^?tVe>^Y3DgyTXNhNU18(1Jrp49B(>zJ#=YzI}*$6KX5&rxa_oW6RgXbcV`Lo0DHg zluI(=&@ZvZPx5%?7Aj;u((Kti+2KliVw=kTR2pVg7`h%}5C!2?|M)aK-$X1YfTSPV zOFW54#sPdLh-Q^Az=8@;2q=d{B8*Bzy9%);@vn%j8ZI`A9`ytgV_M7d>1g|4 z+vnaT6sl}{r8K?$^H!Zqa)3+b^VUpt<#&mYKA9k@ndg50H3t%gOAHl5sss5W0#v!v zQxXE~^&={!8m5|i{hkyQI)Acm-@q{IGTpRkC4xgjeoyf9rLW(O$rpBT5rzHm;dO@V zlRCS*GoYy@40qBQ%HvV5c%(WGCL1ICnoU#`GN!&Pknsz*87d{JZs!AkUz9(kB#$ho zYp_IK-h6Wf6vyblU=o>v=tY^eZM`CHQn)Y4U0wuq>5<`{F3~RjNZo-V%ci>?f zZf&$FhSS;t3Z!dZyDnZmo9ut`)N%2(YGZ}HM(HfoqJPUp$`a39N0`!l z&WpIvr^L_5fMy1E4Sie90kY^Q*@jpgF?vihiUlEFA#BQZJV}-ZP7LVYrlpTroQCt(AeX(u@oJNB~7O=sQ7E{M4V#~ z%IYPEd$``+Y)BzyEy2NTR_UifD3M_0IgV{5CD*R;DPan!YesOT|_}~hK)_; zSc=s?UE_K80k*DXJE_!8jqKI~o?kznnYs3Jd&vw#g}&gis>GzodhluAjd#17ZZ^#C zg7(apxBwR>8#2(5Z0J?V{^I{x@XRh+zkkKc`#VkM`gzyD{)Qm9ud_Dql)aoWszC&1 zUELWmiLVPk% z|FH-#a)>?CGC&LyiETvh@f!Gg3L-MGl|dX-iG$CsQg-eXL}9+{#zm5-ylhG(A2Nyv z4)!43={Ztg&qDOu#y-+It60*+N+TItUkF6Ava=7umI8VJ_9%=PE;?8~ z9esK^$^YyAO*6A;SNxzO#;BJ!c4{LoCpjU`;RXZG9zE|ynD7x5Wo5MzrP0aNHF06V z`%xv*Dh*xT+!D${U}yJ(QJsBRl37>k*kR3lfoS}q1e8PGm^dN){xNoFVIbi~4`fs4 zj}Juvg&|#+U)0iXfM~0g}3hCr%yemWAEOnQ+LYm)MoKSPloCS ztP0W1w7m|kZ2dJ;mK{SEOJ|{hh=nlE-0rr@yUR^KsT-#Uh<)CX==U?w^N))VWzax! z1?tPmvXHOl0o#a( z=?fQD?!KwKde}>df`x-{UPsDjPQ6-QE|B)P_ixj=?>B!^^S0Ya4&P&8nf0iYGkw7I z>`?Kp3o7*3&k+lGOr~^xVwl@b?fe)ZZ|O=8LKeBhcEj!Se{7Tt+D`A;cggnc{?MsNB`#3OKNe(-{xE@kp?zsG<5zXw~=d zJ8fEztNF}T)PefG?nJh*CPZO&Uz6ZHxz}N|K_~y+kQ6P^Z zi=Hq;ac}(g0GrtGP>wTRpHk~I88tJKc{FGL@5Rb?E~J)m@nSGi6ESa<61pf^5iP5x=v@qnGQOh5e&5Jw%Eot5OIV}B`| z@9|o`XI#-{nc@;9O8WbDV(y9#$v7Dx9-^e-w#-)lcqHBg1u1*SOa~Ca6J-Qp5`XfU zvh1$%ndkJ=*NZ1x?8e6(lJVaLq_J0eNO9lbnjXOo)N~D!2lBR`Y`cE>o+3lK^wEg| zYqAQRac_LCBI4}g%+e3s4@31#fR>H7U-xi5&wQZQoDyOeD zQ2*+CuC0O-#%Pd86WNR~m1~JTcw4h`?Dh5xC@rAqa=c?rjqtX>{&_Ytu~f?vnIZk3 zmt;i#eF8xWcmhw>=crhTa!Y3n0D#IY5S4aQsB;5J6Oyvy>sT5i z3U)rykexbbj%>ZX`g0i)nspxUifdl;vGw!jv94i7hR9;!&@_wxQ7PT~+qo|U+=UldDhv>KchO?|DBZOSXU6EPw3WnT<8-Xee2oE;`V* z6^D)X@|-ODVkF0pf_k*0>lGq8C2Dq@S9Y;)Gc#5Gq*U5#(vloR-}CrSEjg^+h@06K zCfOWzS|ZJIagUL7!=Hq&Tk$#q`LZ<5iU{I0=q+ce^|LAmb?NXx{zRiSj?W1)nP=;B z!ns?*VudJSeBw+mrG72rr*1vD(@}=`1@(8&hgzt-3ko{1o+d;AGv^}NawfHT+h1%) z^n$Erd>;U!7xy=M<}*yQ$eeNV^pEX%Z)2#m8b_gKDNpueS7iq|ivnD-Q#qYKAKtHO zmaXcX&3~<&5A!=zELAL^v?j-_OtW-)q z5zY+9f1iQb3dL<&PzmTvjK-6LE-{&HmE2UJqB_^f6tc~gt~y6;j`TGdsxCHdCok!U z%e9v|g>tn|149t!9%|Cepn9`fGxVy2@K}kpFLg#m3f! zjKSZ$B(^PaqXkT+#PltH(O}Qq79ooG%SR8JN7W1Hf(HXXWM&$v(#>suqxPft%j&zc z$6r$xNtyp+9x(!u30SP|(pnQ0y7m&S5b~hW+`@h(yX>BBwN8IeB?8a>rA+Vo05Z*2 zsnCDi(rSIPJ#Xr#uL^xz6@TWitkF>BQKnHx_FtGoNPo)$XtbBUDnhlgt#6pjWtxN0 zX4D+jQt7RnN0qY^1ESq>13++}_}`xw#OG3l4f5IjwL`li+;cY7Mx8DTLG$r6Wnw=2 zl9QlOu645Ue;;~C5LEX_fTu&B(Xnpl2b=11CXc)cJzK$_kz(<*>~}1M`dc76eZV`} zLf$>|e?LQd>VEbD}xg_6+lDFp<0e zwZEFF3}tGl-YjWKgSxGHR6x-R7;gttz&_cs#3Z$4pj(x`??kExU?K6mG)N!EruIv= z)M@v$zJVayUz_GEM2l8k*nOub#>Bo$Z_D|pk}VG&IWc-AQkt)dQpQ9{hqRsl`#x{Q z;e|KJ3@}I>=BX%$IS#1i*QOtn&O*cvn#mo!n#Xo&<0B4?^`5u=-78m;{oik#0x5b1 z>;qO8)*5W43PECkp}?$WP4CW|??xc$_($~HY=;vgmbYWvX9*u!;s5^Lanvv@vAE$| zkX;20hX9@NRpVr@4K=6xNBCl$rJY9GgRDA>#X)OwrFqtQ_ea5GS%OcF>k|O=TMV~F zLzn)815ss&Z)^4cg>kE+w^~EjkMLOKQi<|ghvaHP6=!7JX*Fk3E&ksVlG`ge*$q(e z{(y4Oot~c+T{;^Ewk;Z0y@|TrJ~;EL`Ta5&q0$E~9x`(HzZZQ<7R&t>?Q#d%%are0 zmcCFZLK^62%7*-qTC$1BA~c3lxAd8r$g2Lg{0XEq|L-l6VFO$dO14Fe3|>ux=Qje!mI?9*1Cv7bvB z8H@jjZue26Gs^a*{QVh?Nvt_croX1$(27!(N6EI_F~OKQ z348GDc+5W=yM$vJ7FAQ4_g%Tcb89btXS#fIn54g_G~T6*6Smb{T>qk(+b4l$GSr~= z)5R=AH?8#zVz>!^XUEX2Oh(K2TGFfWn)$%02ufJkSZ<10>VLnCxP?K%Pbu4+5?;){ z%2%nW?KmIuc756>bA%BSx6>qU^XQDB>4RlI=!s?6_1rND^w^|hznS~NPjhZ#%%JH5 z`aqkT$O1mfCxbvS!)gj-MWKFzHSG}epCz*F zX(LHO29oKHNSYkEuD*H4+*z*cMM4znQnPbxW^uCYcMQ^JH#;X=;ywbcgmM(E?}y(p zvU}Tgbtsc+TNAI!tD+4xYFLd={Uq%DZVI)QMoY8TI~`o0fgZ|T|IAZIkfATt+eIX- z`8D{~I0q2qb&f2%EnxazOjvG#wT^#}GHkDR@pat9*Ks#QR=O)%_MfaAdD}Ifx$7xZ zBPIGr8xn)b45QHu3d+V&54I%w1){Cn;gq~r`ljYk_yucz3u-8!hL6(8U}D@v)ci-C zRuC7B^lsJYKKL{t@_a(s@c#MlTtByx@%oJ$LHUaELqI!K>nabTC=jI@D}t9E27#cI z(p(u;%i*jxsq&+~*x*vkqO<3I9>tj@f#LWYdbt5y9eMFN zHt8CQfQ`S59FrOBKpAae?+?;wKV%gW2s$=H;CKf=%MljzaT%$pMyH)4%1R~+9FAAc zpJDa9?fdOA*~Z#nt5r$ommxr!I>KfB_rsXNHAvLg#o#Y>f9g51GC$#Gm>3IA-{$+8 zg%_?R%=K@!)E)fIms#WuW|pihER9yevN92G}ghS^H3*Lu$IHA;5km zAot6nlTfqIk(@8FzNY_=l90c34jsZZbO=eU{>;MN@ds2dUy^Kr{~jqLSiv@?rP`@X ze0*75$Ly`9rYEH64DO`~jUA6FC2b>w%Dd*KMF$VIR$fMsAshk^2F83SC7r_mev;G# z6~Z5oyzh50@;Pct&z2Uq-FDf?AP31FXQIPij4>4*;1Q&Sc z7Zoik7d~+-bdGwe`Z)Z$`3_(k0@x5W-9TPnMrAy*E(81J-#K%qaq#YTQfZnLJRrUi8@R|UKV=_1tZjyHH6g&LmSw2?Tie_3GuE$UOAxplB} zM0M<_d6jRcbcWn-q*Jjp%YZ^>1RGFJkV8Z}#!XHJL?{?Y{yi}N@(-n~qV1KFZ$fW0 zV3}gxb#<;_CmNG;v(l%jgO_Y*BU-S*1Cw})Ddcxzhd45&c(G1{O|qqb6W>gWtf zTwg`s-B^jT{O^ZJ;!qT#Ji+l4$x{4-`XNtZi8~#6nU&9##&eMwN&l|>FBaflSY#nd Y-CLOI-udw(3IDU9I9OaY_l^Jm0H^}E3jhEB literal 0 HcmV?d00001 From 205e71e06e9e3b86ce457650d47ecd65ac8ecfbe Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 18 Jul 2012 12:41:13 +0100 Subject: [PATCH 051/543] GCS- Allow stylesheets to be loaded from files acording to OS. Use "linux.qss", "macos.qss" and "windows.qss" filenames and place them on the app directory. --- ground/openpilotgcs/src/app/main.cpp | 26 +++++++++++++++++++++++++- 1 file changed, 25 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/app/main.cpp b/ground/openpilotgcs/src/app/main.cpp index ec2191956..06825b450 100644 --- a/ground/openpilotgcs/src/app/main.cpp +++ b/ground/openpilotgcs/src/app/main.cpp @@ -229,6 +229,30 @@ static void overrideSettings(QSettings &settings, int argc, char **argv){ settings.sync(); } +static inline void loadStyleSheet() { + /* Let's use QFile and point to a resource... */ +#ifdef Q_OS_MAC + QFile data(QCoreApplication::applicationDirPath()+"/macos.qss"); +#elif defined(Q_OS_LINUX) + QFile data(QCoreApplication::applicationDirPath()+"/linux.qss"); +#else + QFile data(QCoreApplication::applicationDirPath()+"/windows.qss"); +#endif + QString style; + /* ...to open the file */ + if(data.open(QFile::ReadOnly)) { + /* QTextStream... */ + QTextStream styleIn(&data); + /* ...read file to a string. */ + style = styleIn.readAll(); + data.close(); + /* We'll use qApp macro to get the QApplication pointer + * and set the style sheet application wide. */ + qApp->setStyleSheet(style); + qDebug()<<"Loaded stylesheet:"<hasError()) { displayError(msgCoreLoadFailure(coreplugin->errorString())); return 1; From bc5a1dd43bf92f40a8c0438b6a28dce9d68a24dc Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 6 Jul 2012 15:59:24 +0100 Subject: [PATCH 052/543] GCS - added an UDP UAVTalk mirror. --- .../plugins/coreplugin/generalsettings.cpp | 35 +++++++++++-- .../src/plugins/coreplugin/generalsettings.h | 13 +++++ .../src/plugins/coreplugin/generalsettings.ui | 14 ++++++ .../src/plugins/uavtalk/uavtalk.cpp | 49 ++++++++++++++++++- .../src/plugins/uavtalk/uavtalk.h | 8 ++- .../src/plugins/uavtalk/uavtalk.pro | 1 + 6 files changed, 114 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp index f0bc7bf4f..68e695730 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp @@ -39,6 +39,7 @@ #include #include "ui_generalsettings.h" +#include using namespace Utils; using namespace Core::Internal; @@ -47,7 +48,8 @@ GeneralSettings::GeneralSettings(): m_saveSettingsOnExit(true), m_dialog(0), m_autoConnect(true), - m_autoSelect(true) + m_autoSelect(true), + m_useUDPMirror(false) { } @@ -107,18 +109,21 @@ void GeneralSettings::fillLanguageBox() const } } - QWidget *GeneralSettings::createPage(QWidget *parent) { m_page = new Ui::GeneralSettings(); - QWidget *w = new QWidget(parent); + globalSettingsWidget *w = new globalSettingsWidget(parent); + connect(w,SIGNAL(showHidden()),this,SLOT(showHidden())); m_page->setupUi(w); + m_page->labelUDP->setVisible(false); + m_page->cbUseUDPMirror->setVisible(false); fillLanguageBox(); connect(m_page->checkAutoConnect,SIGNAL(stateChanged(int)),this,SLOT(slotAutoConnect(int))); m_page->checkBoxSaveOnExit->setChecked(m_saveSettingsOnExit); m_page->checkAutoConnect->setChecked(m_autoConnect); m_page->checkAutoSelect->setChecked(m_autoSelect); + m_page->cbUseUDPMirror->setChecked(m_useUDPMirror); m_page->colorButton->setColor(StyleHelper::baseColor()); connect(m_page->resetButton, SIGNAL(clicked()), @@ -135,6 +140,7 @@ void GeneralSettings::apply() StyleHelper::setBaseColor(m_page->colorButton->color()); m_saveSettingsOnExit = m_page->checkBoxSaveOnExit->isChecked(); + m_useUDPMirror=m_page->cbUseUDPMirror->isChecked(); m_autoConnect = m_page->checkAutoConnect->isChecked(); m_autoSelect = m_page->checkAutoSelect->isChecked(); } @@ -151,6 +157,7 @@ void GeneralSettings::readSettings(QSettings* qs) m_saveSettingsOnExit = qs->value(QLatin1String("SaveSettingsOnExit"),m_saveSettingsOnExit).toBool(); m_autoConnect = qs->value(QLatin1String("AutoConnect"),m_autoConnect).toBool(); m_autoSelect = qs->value(QLatin1String("AutoSelect"),m_autoSelect).toBool(); + m_useUDPMirror = qs->value(QLatin1String("UDPMirror"),m_useUDPMirror).toBool(); qs->endGroup(); } @@ -166,6 +173,7 @@ void GeneralSettings::saveSettings(QSettings* qs) qs->setValue(QLatin1String("SaveSettingsOnExit"), m_saveSettingsOnExit); qs->setValue(QLatin1String("AutoConnect"), m_autoConnect); qs->setValue(QLatin1String("AutoSelect"), m_autoSelect); + qs->setValue(QLatin1String("UDPMirror"), m_useUDPMirror); qs->endGroup(); } @@ -231,6 +239,11 @@ bool GeneralSettings::autoSelect() const return m_autoSelect; } +bool GeneralSettings::useUDPMirror() const +{ + return m_useUDPMirror; +} + void GeneralSettings::slotAutoConnect(int value) { if (value==Qt::Checked) @@ -238,3 +251,19 @@ void GeneralSettings::slotAutoConnect(int value) else m_page->checkAutoSelect->setEnabled(true); } + +void GeneralSettings::showHidden() +{ + m_page->labelUDP->setVisible(true); + m_page->cbUseUDPMirror->setVisible(true); +} + +globalSettingsWidget::globalSettingsWidget(QWidget *parent):QWidget(parent){} + +void globalSettingsWidget::keyPressEvent(QKeyEvent *event) +{ + if(event->key()==Qt::Key_F7) + { + emit showHidden(); + } +} diff --git a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h index f70d7c9a9..8a458b947 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h @@ -58,6 +58,7 @@ public: bool saveSettingsOnExit() const; bool autoConnect() const; bool autoSelect() const; + bool useUDPMirror() const; void readSettings(QSettings* qs); void saveSettings(QSettings* qs); @@ -68,6 +69,7 @@ private slots: void resetLanguage(); void showHelpForExternalEditor(); void slotAutoConnect(int); + void showHidden(); private: void fillLanguageBox() const; @@ -78,10 +80,21 @@ private: bool m_saveSettingsOnExit; bool m_autoConnect; bool m_autoSelect; + bool m_useUDPMirror; QPointer m_dialog; QList m_codecs; }; +class globalSettingsWidget:public QWidget +{ + Q_OBJECT +public: + globalSettingsWidget(QWidget * parent); +protected: + void keyPressEvent(QKeyEvent *); +signals: + void showHidden(); +}; } // namespace Internal } // namespace Core diff --git a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.ui b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.ui index 1be8020ce..fa3269c94 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.ui +++ b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.ui @@ -178,6 +178,20 @@ + + + + + + + + + + + Use UDP Mirror + + + diff --git a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp index e1aa5ecf6..5bb4d1939 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp @@ -27,7 +27,8 @@ #include "uavtalk.h" #include #include - +#include +#include //#define UAVTALK_DEBUG #ifdef UAVTALK_DEBUG #include "qxtlogger.h" @@ -75,6 +76,19 @@ UAVTalk::UAVTalk(QIODevice* iodev, UAVObjectManager* objMngr) memset(&stats, 0, sizeof(ComStats)); connect(io, SIGNAL(readyRead()), this, SLOT(processInputStream())); + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + Core::Internal::GeneralSettings * settings=pm->getObject(); + useUDPMirror=settings->useUDPMirror(); + qDebug()<<"USE UDP:::::::::::."<bind(9000); + udpSocketRx->connectToHost(QHostAddress::LocalHost,9000); + connect(udpSocketTx,SIGNAL(readyRead()),this,SLOT(dummyUDPRead())); + connect(udpSocketRx,SIGNAL(readyRead()),this,SLOT(dummyUDPRead())); + } } UAVTalk::~UAVTalk() @@ -119,6 +133,17 @@ void UAVTalk::processInputStream() } } +void UAVTalk::dummyUDPRead() +{ + QUdpSocket *socket=qobject_cast(sender()); + QByteArray junk; + while(socket->hasPendingDatagrams()) + { + junk.resize(socket->pendingDatagramSize()); + socket->readDatagram(junk.data(),junk.size()); + } +} + /** * Request an update for the specified object, on success the object data would have been * updated by the GCS. @@ -219,6 +244,9 @@ bool UAVTalk::processInputByte(quint8 rxbyte) rxPacketLength++; // update packet byte count + if(useUDPMirror) + rxDataArray.append(rxbyte); + // Receive state machine switch (rxState) { @@ -235,6 +263,12 @@ bool UAVTalk::processInputByte(quint8 rxbyte) rxPacketLength = 1; + if(useUDPMirror) + { + rxDataArray.clear(); + rxDataArray.append(rxbyte); + } + rxState = STATE_TYPE; UAVTALK_QXTLOG_DEBUG("UAVTalk: Sync->Type"); break; @@ -446,6 +480,10 @@ bool UAVTalk::processInputByte(quint8 rxbyte) mutex->lock(); receiveObject(rxType, rxObjId, rxInstId, rxBuffer, rxLength); + if(useUDPMirror) + { + udpSocketTx->writeDatagram(rxDataArray,QHostAddress::LocalHost,udpSocketRx->localPort()); + } stats.rxObjectBytes += rxLength; stats.rxObjects++; mutex->unlock(); @@ -476,7 +514,6 @@ bool UAVTalk::processInputByte(quint8 rxbyte) bool UAVTalk::receiveObject(quint8 type, quint32 objId, quint16 instId, quint8* data, qint32 length) { Q_UNUSED(length); - UAVObject* obj = NULL; bool error = false; bool allInstances = (instId == ALL_INSTANCES); @@ -742,6 +779,10 @@ bool UAVTalk::transmitNack(quint32 objId) if (io && io->isWritable() && io->bytesToWrite() < TX_BUFFER_SIZE ) { io->write((const char*)txBuffer, dataOffset+CHECKSUM_LENGTH); + if(useUDPMirror) + { + udpSocketRx->writeDatagram((const char*)txBuffer,dataOffset+CHECKSUM_LENGTH,QHostAddress::LocalHost,udpSocketTx->localPort()); + } } else { @@ -832,6 +873,10 @@ bool UAVTalk::transmitSingleObject(UAVObject* obj, quint8 type, bool allInstance if (!io.isNull() && io->isWritable() && io->bytesToWrite() < TX_BUFFER_SIZE ) { io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH); + if(useUDPMirror) + { + udpSocketRx->writeDatagram((const char*)txBuffer,dataOffset+length+CHECKSUM_LENGTH,QHostAddress::LocalHost,udpSocketTx->localPort()); + } } else { diff --git a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.h b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.h index 6f0bf2e8d..3d2c69d7b 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.h +++ b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.h @@ -35,6 +35,7 @@ #include #include "uavobjectmanager.h" #include "uavtalk_global.h" +#include class UAVTALK_EXPORT UAVTalk: public QObject { @@ -65,6 +66,7 @@ signals: private slots: void processInputStream(void); + void dummyUDPRead(); private: @@ -122,6 +124,11 @@ private: RxStateType rxState; ComStats stats; + bool useUDPMirror; + QUdpSocket * udpSocketTx; + QUdpSocket * udpSocketRx; + QByteArray rxDataArray; + // Methods bool objectTransaction(UAVObject* obj, quint8 type, bool allInstances); bool processInputByte(quint8 rxbyte); @@ -134,7 +141,6 @@ private: bool transmitSingleObject(UAVObject* obj, quint8 type, bool allInstances); quint8 updateCRC(quint8 crc, const quint8 data); quint8 updateCRC(quint8 crc, const quint8* data, qint32 length); - }; #endif // UAVTALK_H diff --git a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.pro b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.pro index 7fa575cf1..ca267a0ba 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.pro +++ b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.pro @@ -1,3 +1,4 @@ +QT += network TEMPLATE = lib TARGET = UAVTalk include(../../openpilotgcsplugin.pri) From 41c0736b9bb5d95c2642cc117d8c1f3ac7fffd34 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Thu, 19 Jul 2012 13:22:36 +0100 Subject: [PATCH 053/543] GCS- Added Expert mode setting. To make it visible go to tools->options->general_settings and click one of the checkboxes to give focus to the form, then just press F7 and you will see hidden settings. --- .../src/plugins/config/config_cc_hw_widget.cpp | 12 ++++++++++++ .../src/plugins/coreplugin/generalsettings.cpp | 16 +++++++++++++++- .../src/plugins/coreplugin/generalsettings.h | 3 ++- .../src/plugins/coreplugin/generalsettings.ui | 14 ++++++++++++++ 4 files changed, 43 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp index 97cfccd47..35a3f4c9a 100644 --- a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp @@ -36,6 +36,11 @@ #include #include +////Added to allow expert mode +#include +#include +//// + ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent) { m_telemetry = new Ui_CC_HW_Widget(); @@ -43,6 +48,13 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent) m_telemetry->label_2->setPixmap(QPixmap(":/configgadget/images/coptercontrol.svg")); +////Added to allow expert mode + ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); + Core::Internal::GeneralSettings * settings=pm->getObject(); + if(!settings->useExpertMode()) + m_telemetry->saveTelemetryToRAM->setVisible(false); +////////////////////////////////// + addApplySaveButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD); addUAVObjectToWidgetRelation("HwSettings","CC_FlexiPort",m_telemetry->cbFlexi); addUAVObjectToWidgetRelation("HwSettings","CC_MainPort",m_telemetry->cbTele); diff --git a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp index 68e695730..663f5e545 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp @@ -49,7 +49,8 @@ GeneralSettings::GeneralSettings(): m_dialog(0), m_autoConnect(true), m_autoSelect(true), - m_useUDPMirror(false) + m_useUDPMirror(false), + m_useExpertMode(false) { } @@ -117,6 +118,8 @@ QWidget *GeneralSettings::createPage(QWidget *parent) m_page->setupUi(w); m_page->labelUDP->setVisible(false); m_page->cbUseUDPMirror->setVisible(false); + m_page->labelExpert->setVisible(false); + m_page->cbExpertMode->setVisible(false); fillLanguageBox(); connect(m_page->checkAutoConnect,SIGNAL(stateChanged(int)),this,SLOT(slotAutoConnect(int))); @@ -124,6 +127,7 @@ QWidget *GeneralSettings::createPage(QWidget *parent) m_page->checkAutoConnect->setChecked(m_autoConnect); m_page->checkAutoSelect->setChecked(m_autoSelect); m_page->cbUseUDPMirror->setChecked(m_useUDPMirror); + m_page->cbExpertMode->setChecked(m_useExpertMode); m_page->colorButton->setColor(StyleHelper::baseColor()); connect(m_page->resetButton, SIGNAL(clicked()), @@ -141,6 +145,7 @@ void GeneralSettings::apply() m_saveSettingsOnExit = m_page->checkBoxSaveOnExit->isChecked(); m_useUDPMirror=m_page->cbUseUDPMirror->isChecked(); + m_useExpertMode=m_page->cbExpertMode->isChecked(); m_autoConnect = m_page->checkAutoConnect->isChecked(); m_autoSelect = m_page->checkAutoSelect->isChecked(); } @@ -158,6 +163,7 @@ void GeneralSettings::readSettings(QSettings* qs) m_autoConnect = qs->value(QLatin1String("AutoConnect"),m_autoConnect).toBool(); m_autoSelect = qs->value(QLatin1String("AutoSelect"),m_autoSelect).toBool(); m_useUDPMirror = qs->value(QLatin1String("UDPMirror"),m_useUDPMirror).toBool(); + m_useExpertMode = qs->value(QLatin1String("ExpertMode"),m_useExpertMode).toBool(); qs->endGroup(); } @@ -174,6 +180,7 @@ void GeneralSettings::saveSettings(QSettings* qs) qs->setValue(QLatin1String("AutoConnect"), m_autoConnect); qs->setValue(QLatin1String("AutoSelect"), m_autoSelect); qs->setValue(QLatin1String("UDPMirror"), m_useUDPMirror); + qs->setValue(QLatin1String("ExpertMode"), m_useExpertMode); qs->endGroup(); } @@ -244,6 +251,11 @@ bool GeneralSettings::useUDPMirror() const return m_useUDPMirror; } +bool GeneralSettings::useExpertMode() const +{ + return m_useExpertMode; +} + void GeneralSettings::slotAutoConnect(int value) { if (value==Qt::Checked) @@ -256,6 +268,8 @@ void GeneralSettings::showHidden() { m_page->labelUDP->setVisible(true); m_page->cbUseUDPMirror->setVisible(true); + m_page->labelExpert->setVisible(true); + m_page->cbExpertMode->setVisible(true); } globalSettingsWidget::globalSettingsWidget(QWidget *parent):QWidget(parent){} diff --git a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h index 8a458b947..6c77ab065 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h @@ -61,7 +61,7 @@ public: bool useUDPMirror() const; void readSettings(QSettings* qs); void saveSettings(QSettings* qs); - + bool useExpertMode() const; signals: private slots: @@ -81,6 +81,7 @@ private: bool m_autoConnect; bool m_autoSelect; bool m_useUDPMirror; + bool m_useExpertMode; QPointer m_dialog; QList m_codecs; diff --git a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.ui b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.ui index fa3269c94..9e3dd68df 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.ui +++ b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.ui @@ -192,6 +192,20 @@ + + + + Expert Mode + + + + + + + + + + From 2464fe9a2eedf77444e9fbb3394b9d696d45dbf4 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 20 Jul 2012 12:47:03 +0100 Subject: [PATCH 054/543] GCS-Make flight mode switch and accessory channels move acording to user command. --- .../src/plugins/config/configinputwidget.cpp | 37 ++++++++++++++++++- .../src/plugins/config/configinputwidget.h | 10 +++++ 2 files changed, 46 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index 7952b3d70..e9a4e6a6a 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -50,6 +50,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent) { manualCommandObj = ManualControlCommand::GetInstance(getObjectManager()); manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager()); + flightStatusObj = FlightStatus::GetInstance(getObjectManager()); receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager()); m_config = new Ui_InputWidget(); m_config->setupUi(this); @@ -458,6 +459,9 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) break; case wizardIdentifyLimits: { + accessoryDesiredObj0 = AccessoryDesired::GetInstance(getObjectManager(),0); + accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(),1); + accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(),2); setTxMovement(nothing); m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions and press next when ready"))); fastMdata(); @@ -476,6 +480,8 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) } connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits())); connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); } break; case wizardIdentifyInverted: @@ -503,8 +509,10 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) fastMdata(); break; case wizardFinish: - dimOtherControls(true); + dimOtherControls(false); connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture below mimics your sticks movement.\n" "This new settings aren't saved to the board yet, after pressing next you will go to the initial screen where you can do that."))); fastMdata(); @@ -572,6 +580,8 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step) case wizardIdentifyLimits: disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits())); disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + disconnect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); manualSettingsObj->setData(manualSettingsData); restoreMdata(); setTxMovement(nothing); @@ -595,6 +605,8 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step) dimOtherControls(false); setTxMovement(nothing); disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + disconnect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); restoreMdata(); break; default: @@ -1060,6 +1072,11 @@ void ConfigInputWidget::moveSticks() { QTransform trans; manualCommandData=manualCommandObj->getData(); + flightStatusData=flightStatusObj->getData(); + accessoryDesiredData0=accessoryDesiredObj0->getData(); + accessoryDesiredData1=accessoryDesiredObj1->getData(); + accessoryDesiredData2=accessoryDesiredObj2->getData(); + if(transmitterMode==mode2) { trans=m_txLeftStickOrig; @@ -1074,6 +1091,24 @@ void ConfigInputWidget::moveSticks() trans=m_txLeftStickOrig; m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false); } + if(flightStatusData.FlightMode==manualSettingsData.FlightModePosition[0]) + { + m_txFlightMode->setElementId("flightModeLeft"); + m_txFlightMode->setTransform(m_txFlightModeLOrig,false); + } + else if (flightStatusData.FlightMode==manualSettingsData.FlightModePosition[1]) + { + m_txFlightMode->setElementId("flightModeCenter"); + m_txFlightMode->setTransform(m_txFlightModeCOrig,false); + } + else if (flightStatusData.FlightMode==manualSettingsData.FlightModePosition[2]) + { + m_txFlightMode->setElementId("flightModeRight"); + m_txFlightMode->setTransform(m_txFlightModeROrig,false); + } + m_txAccess0->setTransform(QTransform(m_txAccess0Orig).translate(accessoryDesiredData0.AccessoryVal*ACCESS_MAX_MOVE*10,0),false); + m_txAccess1->setTransform(QTransform(m_txAccess1Orig).translate(accessoryDesiredData1.AccessoryVal*ACCESS_MAX_MOVE*10,0),false); + m_txAccess2->setTransform(QTransform(m_txAccess2Orig).translate(accessoryDesiredData2.AccessoryVal*ACCESS_MAX_MOVE*10,0),false); } void ConfigInputWidget::dimOtherControls(bool value) diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.h b/ground/openpilotgcs/src/plugins/config/configinputwidget.h index 418fbdfee..bc27467ca 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.h @@ -43,6 +43,8 @@ #include #include #include +#include "flightstatus.h" +#include "accessorydesired.h" class Ui_InputWidget; @@ -91,6 +93,14 @@ private: ManualControlCommand * manualCommandObj; ManualControlCommand::DataFields manualCommandData; + FlightStatus * flightStatusObj; + FlightStatus::DataFields flightStatusData; + AccessoryDesired * accessoryDesiredObj0; + AccessoryDesired * accessoryDesiredObj1; + AccessoryDesired * accessoryDesiredObj2; + AccessoryDesired::DataFields accessoryDesiredData0; + AccessoryDesired::DataFields accessoryDesiredData1; + AccessoryDesired::DataFields accessoryDesiredData2; UAVObject::Metadata manualControlMdata; ManualControlSettings * manualSettingsObj; ManualControlSettings::DataFields manualSettingsData; From ece35e702505641194e13d5f8b12e674ec30f7c3 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 20 Jul 2012 12:55:37 +0100 Subject: [PATCH 055/543] GCS-Added missing PipX PNG. --- .../src/plugins/uploader/devicewidget.cpp | 2 +- .../src/plugins/uploader/images/pipx.png | Bin 0 -> 184786 bytes .../plugins/uploader/runningdevicewidget.cpp | 2 +- .../src/plugins/uploader/uploader.qrc | 1 + 4 files changed, 3 insertions(+), 2 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/uploader/images/pipx.png diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp index c22e548b0..dec1fefb7 100644 --- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp @@ -95,7 +95,7 @@ void deviceWidget::populate() devicePic.load("");//TODO break; case 0x0301: - devicePic.load("");//TODO + devicePic.load(":/uploader/images/pipx.png"); break; case 0x0401: devicePic.load(":/uploader/images/gcs-board-cc.png"); diff --git a/ground/openpilotgcs/src/plugins/uploader/images/pipx.png b/ground/openpilotgcs/src/plugins/uploader/images/pipx.png new file mode 100644 index 0000000000000000000000000000000000000000..47c8bb4e1885c159e5387238a2fc2ea8d9c84fcd GIT binary patch literal 184786 zcmZts1z1$w_XZ53h=2$Pf(S^Lv=SoS-7Sqs4Jq9z(#_B*9n#$>-7s`_3^n8oFvL5k zzvusb*ZVRT%s!j5*1p%hYR{P+qNE^+`Hbip5)u-ow3L_%64K*5#4il(DPpENgKq@! zhW=Gb%K-@qh_viH|GRb{+6Wwv`Xl`ZX~n1iZ=^^RC=}g{h=rvPz>v`BAMpJdljl;| z6F#W>v%2rNVZ{U9zZh|@QYTD={%7oi3dHNLsYn5iHMWEZsXufFI9{GT@UQX^Zz4R= zExtR5%fDC8L>?v|#;&aYt=jRrit4{bdw|iA#_w?cqwLFo2SLNDKM?;>Xc&o5@rT0b zNG=MLng2lipW%Pa{!3x>#u`noVd+0Jo(H30Arn4%K>n9)$G4}C{sV;u78ycqp#A5q zFLF{re%vA$`2Xm5PnSzot^M*pXgMAF|2ZE?BHY05KZlC&D6u{LKdlJ#{|Wv7hCnnH z7lmF{z(b}zFlPwtOX^}rT>L@C=Ma7Mdb5WAKS^ZT+>Im2KMYF!zx?)JTp|7cqY8MA zg-ri+=E=Vm*6dnh22g7ry!a4nukk4xgbEJ-Sn+WE$E%2GCfZ{(B&1zbpvtXrIYuGJLdo;o`0EhWp&OxJ79vfg46jL%d@1O1JAF|kq_*A+KL2Zy?+HzA zry-5rWdL3mB9DZTCtyfO=Rv_EA;;kkh7+rgi{Is8BXy7?$v$LAuBg;=xZTn+kQfQ6 zWAV=%KUJJQANDr7R3#`cV=3Hv~KSa7Ue=aNLrjQIOP2dCa*HTHp@!o8!Mn z(LzDWn&~*_M?%u0$aU)7wY}><^9)7@KMtvZ9H*2%#S{f&BdmI0UWm6!Mcn+-SwRl| z>;-848|d`Wdjxq17y8D~AY^l2fu?gEA3gnm>3TJ$P?ns49*mIs_QVrWB$C)EN>3?D ztHY<`Kq#+gse>*wj0aCQ+VYP7Peth=S`m~kB4jMAo8Q#y*u-8-f zvnX9gN8rACoPek)JhZuoeexu8Yttap>c)4$Yf5Gn)%z!p9?P%Hh;J5bVXh!K(l}q4{(+NJVL zgr{KN4#T;*8>@KWUorCa!v!e>n=`h9VrTNU<#2Ck`yV z1+P9RIIEmacrd*X1d$q)Pi3Q?QRI+U{`K(~frvIi$dU|gG2;Xb&1!G&qWCFR`hX~6 zjXxp4@uY6)nUK?~iDjHlQbUA^#eSkC_$@;J1F_o=pbMa@{e2M_jdhrkDJtEjgYwa- zs*4E$;URuSCFK@y-Y6(Y`oF>Q-+)dqFm4FdI0rnm%7+;KL7U^`qp2mmgSX4U;+>1! zph!fn7NaaB^q2IGKAZ{X>2Wo=_GYnC)K9)KP<83r2|Dp70)NY9IG=JUWodO45NjaH z@e%5WJn34U71ICdrb|7H1ekd3vwu5ad-aq;e(*V>F#IXhubxv_yXf~${1QEsnm{=6uT50q+9gtQk`tX9>ykWA z0@OBUs@0i8%nOil5jR950!t#L5E?y>$x3m!!#^+=kJIGl<#U$Fy=2)Z-r?A&sRtPS?J4=k?lcIG>Pw%KbZ_ zCKE=>ILOLeUhGv(Z*b0xgf#T@PrPs$4Ys37Uoy2cj<}-VoUW^`=3?rA>ViZ zuhDggP~~Do)cVW+mStjWtZ1Ui@jrpr#Lt=7JPMy@9aH^FGsBy)Q2_islG@F0hz zN0V#sx1?H*PA^yUKT7;-v9PrcdT)Il{^z@I`N2CJ>U_=HnPCLo#!JsbDu-9;FmWuwHZ9AmD^?gPT0SAUpwuKq@*OnZ&;87LEi-;q6(cK9O@e*#2dDO+&&)|#35_M zE*Q%$G6ALfDf!IjpG!WC1voZH>k5{C19)VyJ6iOU01`?5NFF_6^G}|2p#7*9Lz#dgQye1}eu$BCWYN!SB%xEl>uzXP*1x!R=qh~58zI(4Komq| zaz)2|?^~msI!y-c^SF$A{5P^FNzUl#F#z-44d{US0qhv~pZMzV^)oE6i6gj-fqp+W z>S?Dj{Ql%mYWBnivxs#>{j1YWPd>?B%X1Kf#yei#N?E!{M=uFKzRT@s`0_Xk>9yn= z$1!0N64(isV2*Pp7Sa5fU6|!WiZ$x}ZcbFF$5CTJjn~!bR<+E|mjW^nGzp(kV+c+t zaN0+;o}gp%h~kiui%bzv)CybHIj9~LsBWGLy@uV*+-pnj+-=+5nXX9jDxRgy2;}8B zWZWK@)ytm+3Eof;xf^ai?Ay-$HJ^{IpJ!m)6QI0nh$Yhp%~BqI-!>YzJpK3#u*XKS zg^j3K;Ybp#KL`UA3p79qCwZ`2g&Cfds}CdTx;i?p?Uy^FM}y7tgeSjhZdVESzt(Hs zQoBR$LDr)3QlqyEyn*)b_;y`T5iWkJB>l+n6K_;wYe`Za1Y<4!jB&-e-S6rpNTJ}U z*DpHT=LtQEgrPCoIhhX>d{3Ah`FSi|h0(t0cx6RDw&$*3sdxz>u7bK`8u1&?qy6+_ z1R zMZ{j*(N@B6H)zbf)@N*bnin-;R-}7X1J<24yVGo(W0Y@Wn+|4(VRS$;(Kg<0>gNYX z0hz4V$`}`&toM?eZ6<{py>8qbG4Kv1nQunO_~Q6ww;(2;(7`z6I^ayFjGeXHzE6aV z3>eM#y=1$%b9*0?l{4!g)@>`tKLoK%3J3e+bIJ-LBzpFYYzAi4#Wj2CNM0Q1ZY}pd z^+2_E7u4k+tqLsd?e;D%aBgqa{RVAzAb3V`NQWbMpy)GGL#Cx1NXS~Co2Y&?TFOAD zM;g0VdDrktBhfY^!H!mo_{CmhTYlRI2-WXKC`q5OXW2;NCM4teVbEwIn5t^5x5B{( z;>OAaAN8JUmbqmF(g?};X~mA#w;zOqoadp?#EkJ1&PexL28mVOotJu=>QIg1nka8Z z3X5x$DH{WDB4phY6i*nFz1~D2nBT8fBj2qR-_M`yWg{6iPjjew9f&<5IDfHhNrngi z>6X?`$C-QhmM$&NR=*5{NeT?b+RyZ}A1XNHmEzi~h;#mps}z3#S}>X2=?V8#BHn8W zohR!qFS^W{@@n==y2{^Mc|?C0@YRvXO>l^s>w?ZYIRhYQwYF;u&M3!aaL-pJF7y1H zQrDaC^42-CMh=hhi>+bwooCZiLCwYud|N7A9R)}{O%GJ>ayij9305r#V? zEoLF-;_YJKc&!kO;u9F$MXh@nXcNRJ$}(ued*;-L2(R6$h>E)?i(uZcu$k1ea%X_W z8;8>rxAW*&uafzk{Z38e3YBXEz(W@p;sf@5rCK>w!vN**A4yi+ z4C?B4op)b7hCT&#L~(fg3|xfNNslt;r5k>}P?M2mLrG-~G4L0Xqv2htd48n3HIY?q zWzx3AOMDHzQ;k+_M+fWPNH1(Ft1LO3F{|+C_|hhq@fCW`4aMJ<{&x0hJC(1B{$cxU zXJCwWf`vj$K+TGH6+ma=J-l+4<>(W14~AT~)r^~eVr(6B$OuX%`tplYLn9Tc?o&N2 zurZT{pLez9bHjLYB0@fZdi zuKY1sr9{SmxSA1Xc%K?y%hV|IaZuV=h6INZ+<^vQt)`7T%>{rKpAc>~E|nKZv8zTV z?_WBw$1}?9upYKCec95tDsV_Aj6k;ht(EbCyZYhn)Rva6SUXI1kJ!az`a` zR+9moV>6Ps^P`-DqMhBBCq?=3k6-ytfxA!?gLA!ZN);XEGCzc_NwkQMk>(J0+U- zQb)WZl|hOK5h{%DG*9Pc7)anbGKvXvIV%;~eYxLa1rFamhW1EFgwoLY;v5<#Zv_Bx zn8EVYcafA3|5^XvrC&pF6b2HTHSw9aGt5gSk6%U&G>6#0<5N6~M}lSBiO0{~n?zMO z_;;T^TW(_QFaL;5ikD;b>rKOZP3Z3Aslr|hMzPY@0lwm#O=7G4GJB1xA?#x|*n-^Z zSg>-X7mIZf6ZdfLvjBPrZ?Jnss?I(Mrg^xa5iMN*DF(d~g9GwY>CG|VH`;{X_X+5g zcoEr`DUDHF$H>@Ru5T|b-uqTqv&8=poN0#c)ah0a#jK5W=!}%KC<0_8BKDI9o9hDi zJXLc(hkSK)Ils#9?@vxmsxnT5H$C0lZc52DjR^Fyz29(H;hI^0f}fxo4MMRdq!Dos zC%woU_qFDI!95zu9sbc;$S-5rV84JP(vE5zub0n(M{cw*l)RV;y<#8^iIMDQZtShI zfd<9#8z+qeHn{(m_qywyPE1plgz*fyU2i@O~=!4A#5; zvN9LvTy=L)kT*wp%d*=AZKe0EyWR4YgOS^2Z-`n3l2I) zxlPwV799xsM2u_4la3);su0WV{1Ih-&h*9zi7NPT;{ZxAho_#+wtQyW*94YlrXVK{ zR;ViCgF)Z!s8+#k(5E`9Ii=@)Pvxa*1;JJzk1`g`&jnQ>j>;X;^pZb339k)lR3qhA z^es` z5DI8{>D`r+vhBAi8|c8o0uu>faLxNu`jfiER>CevBwy-DK6LZ+^8nf$4s{>L_iWW| z>BWmQXWsKsXtxcl&j{Y4+!cbNTnk)yqC_Jj9dnc;Al_?D(M`{0u8tI40?40`7UFU@ zgoO%G`}9W}sJE@{N*8i06g%GMVK8j-LHg>XGAnR1@Tx`j=itX&klVvDXH%J?AM0Na z{TTvQO;)ojwH%+Y7W}A>jbxyRcd+WU$1hS>S{hJ4%0BJP^7mYb|GIFdG_BUdm%S|Z z<*cTkb=iPR(SPlCTa$}To$=>7VTD`j-1O_X5om@(f$Q2Jg_%znA25bdG+r~_?1=KH zvqPn_Dr{s}Yo43%`Qnv!iI|;q`y?_nOa za>-YlkyEcOOU>)Hlk{@WFp7fc1phooW9ICD758q6Wl-La0&uCUMpBrDz`!JwQl=}W z(9fy6EuMkWRBnL2tGeKQImNYZS3t+MY)VV)3cY;#SmVkqSix?nIzJm67tA-1Bp%ld zdQr>}D=)wsF4P7aD#`AFE-JnuG>}D!%}F8y$g;4gh4^HgO+!K)1l=b4x_OJ5kg6$& zf1T}Gvdfo8kZLWh8U>?obo@**GQ6r|~OSo5f5d7 z&>k-q~I3a4SUAY&~V9=GTA<7rjq3KIrVEV!HztGL*!j* zX7g;iJGurqbLwuaW&4tJg#Cg{YLQ#b;(Nnym{(J5ykuXI@@6UI1lM% z8{69>|Ju)!nx_Z&Yw40r^~)FL#x&NFQkZ^Bk!wW1>sT~8r_YoUSMH&f-3BceDfTJ0 zaBrQ#$p-nkQClHm9nx0yxMBC0T6UO*d^g8;LgC?WoO+uqhkVgv(Sf)#1YQ!mIaWTM z=wJ+myQQ)A#xL0$1&3|jaq72e3yEpf=JVdKsyECt*EPIB9K-z<#WK?dP4_v=hHzVE z$-I7W(B0YwGu#I$0rZ1Bn+O62HLjDeR>z!6X4YsIdOCYWlu6NN1cUyOBWSGsAzqZYf%+&+UiW{OTc|{{Hm=|EV$;5F)1DE0Hs{8m>UhXjoUsMQJ~p6*XR zjW@b-qr#9G4b@wlyzs4_-zq#30ctvuA<=t<0<3Oo;~)Eu>%wSMuck;Gys?k)0-y1P<5=Lazsro0jj+}21Ww3h2g&Y_#( zt8Vf|)Q+6(%l7eE+KhNG@o)S!KPOg4xHMgGr)lt?E3lAr&AMYOu$6v6Y+?7dUzdEpUeFBlO>g_vJG&cjkT|Z2BlAmhaX)JTABFc>j(W`zr;Bf&%0)2o zbDg=FH`EXlN=MK2-QrYGSM zk(pMO7U^KnAc|+B&2bN1(iZLPQ>#!;txpIg7aH1%%RZq5+f?n_$6RL(_6PdOc}UZO zcI^HKjHd}~D-rsc7L#oE{ES@r(i2zLv3 z&@bOZ$aH_8l;P$6Go#AW4)h(xJ|~&)CnQXFAp?AICo63A-YZ%)z>0-}_4Zqp8tweI z)ol?eNv3SkG0IeaowMG3PZOak$}8Jj^^5jZ18DId#L80iv1`_h)7Kpw1hdBAwZDE# zafIZb(A-Y%{5)SpH+yrW{;_7E7)QrmVCciC;FsHsOgvC^WoTgRcSR9C;$T;5cfNK&d=8s;TevJkUX(P|9YsQKT>vBHO(#{J2N7tc$q z;>@VTjd(H|VKwsvrSaw3OAc>!Buq4uBn59};NxIG;x~Q!cj+sZJ~nxu5xUp2GH_Jn z7F?*73Z!}ciqW5vO-f*B#_(-cfEim zIyg+h;AL>-W?1c$4P@qAa+*v)%#eqWM2TeodHNcp0C&R0E+pu8t++Vx}2C4R*` z72>sgiKX%e$tE^}>IW7dMrC>c4pF4mG*h|fRinDBk^D}zf+8;3mRK3kJHB{=4O32tf zX-E8|IWT)emB`$NNw?uY%lRmwb8~numYV4XyF6`uIu*HSF;~ju`jv;B1bmulUOn;K zwj_n0Zk=bf!eBn@XeW2|bL0ipD>r0$F2iCMyzRXytMJO|=#k;f$=Wbbal(PmnYfV$ z2yI`GU9*gXxW^>flLy)%7Bjjhu`l$gxj6B?gf>-R#a+()Jm7JdN~vYRYtd7Al?rl( zL~JkVqIwgiw_*O8dOD;iR`m7qg|TJMQe0xg^ZRUU;Ec|7dc>zeBY3zG&nzEv3B&OX z7b(Tvt-}nEDIZA+u!2T!?Ez)X{EP+=OQ*ce8+*>0VpQU2Pa;nXC7njr%-i);pl59M zq8p@6ZZoHLD~@$gzi2Gd1@72(JM+&^<*M=ijB76vkaW>5(Ug-UP?ZsvHP(mk*0_#j zTL-3X%hPzrvYuWQ0h6;mD^c^kMrEF%Sm=LWu!r4y-{vvH;rsXSGHr}6^~_NTq9u{M z0s|f-ZEjnv?$hJidcPYwKh=8|xW%FxpONP#;p`L7-S%0Ms=k;A`aTaJuxxPZq+0i- z6O<@F+pLvtl#A2*PEX)t^E2acK@G$>)fI;-eBvT6d9ivqr+t+|yu@uO3K@ zjWq8Wzi-qjo5ncftuiMPkT*Z$VwW){= zr8cN}vVU$&TX)!(oCY-6bS|36r&u55M^x=Cg0j-I0Wzoya;~E=4v74!OENt4J-XLr zb`cS8tW1Bt+yT(fTe_-^0Zbg8q!;M0QFz-Ci(j8ht0ARsH;miMa>os=nOYCUm`MQ; zQsxu616$m?)u?B>LV#^h%!OC+H9H9`9^Yr}XJ!~P*{3#^pgtz2Eoz%_3A2X&>VA~& zMH6ZoECYg6+}ab276JCfzcCDrKc5?Jf+O^`qgh z=@xSstR_Hxy9btu%_k+&ug&D;+CulW$y=4fhut!z?&=i7dganTF7wO6H>Uc#Gy#7B z7@HjJQ{m{yqWx^CRfD+pG@zIsne^|Q#%KHZT;E~pn$$e z?UlZeJrSZq=i(z!-mr^zskK1;;sxilW^rWowwKZp7G-XZRocGB&PpH z&%iHvD*S#{D$AmtPyi#g)9`40z5b2Ra6LDAj$>>#(f3DlQvIs<*r(Gp9y5u77Ro}! z-+nU*h)Ee-_Qd~s`)<%CZ)>G$f=k5t{6q08+t({i#wnii`x7~Zo*>Sx#YY19)u>E) zBrjAVTw2l`rDnuptrwFG;*>4#ST%tb-3o;2RAm#i$(%rVLWvk%WG`_c17_o0j-+^8{O#=s@4dMl7Dg-^z&z-h<%PeC&-M-#JOidcJJ4DUdMdyXmWiquSxE~< zi(4vPa1L2|rI=KemS*S_xW`7tuN=^dA)zeiN5NC~5q1kfBP!4?NHR)wd~(Tcd#`Uj ze@0{0*`ht6>m|Y4PX+62-+vF+%9bi2#^1_C&PsvlX|PBVj4SLY9G)3fI!ts^4zjab zkACx$3OjF@&^3Ii^`>=^K>pTp-`I2!Wp{C?oo+yzr53xWy3AB=iDCxI4$w?GZ4HRa zXPdZkN1>y;5Mf}{+MfJ;9;)hQQ?{i}Q#Cd^>o9z(cITG7&!frVbz~F9R%yc9%(^nV zrJueI_km}wi{2lKd1zb7S@s(>%lNCg9K34l6$OtHxMW2AyUQQBcl8@XC zbQ)c$<(TXI+>DY?<-{0y@s!9jSxQxL#a%uOM#b*=?P=6Ce~Ie!yDFuKAp;kR9D)np z_;neR^gh$4rhF-Rjdu{re3@PPZ~pw`6@RaZ2)JfjG;y4SWj|xfBB&5%)VjH%9{i z&leLT@1YYgl9wuU;h9MUysjfytnqRQDO(ns zxE#*MwX~h5|M^2EVRHYR_bg_VPto&oV$|9vnJIdN$8+^%5IfAjOfj>3 zYaruf*2Kt2mDZ+JHYC-yiTBFtt=AFUBYN^McBz9fy2EYpht7ZN*ipw&jN=(4Fcx!1*Mk=9mn0wK+g z^MYNsF|JQACP`lKjiTqq#JV-BmxH)lhtV??9&C~8KB}ms z71Jli`J00Z*Bal{Xq8XYN8%XV8#!y#&wruT;n`kpmn{?HOm3lYx1NkQGjKaaSE(qY zW>H$~oo{C6OT8XeIh4#bTH{f~K$(dPe|FROaIP*DlnND7oimGc~oOqa3POPr%{w(JEV+xZC6>Pk7ataq}^{qBO zuol$_$h0RSMP_Ky5rAm%F&I#n5>n@`gW9gfinZ4^p0=5xX@N(pj)2AHwj18aX zt}c0vX0o0Y64)T`AnoL$nK>@M&y@s0a5@^T+8RnYN$?_<)M#XDsm=q&V$}`Xyc(t{4;kO5e{U>I z#{#gPk(_d4|MHPrfI$L{&5B5r!kKLVO$xl4@m*@t0;{H!JGu&?JhzKD(L;Ax&g4Ax z*>~TfN0{YVl?+}KK?E&esgv|kZ|p9-Tt{yb!CP99;tMI}(! zQ_O_gfTK`txJkE=MZvr(-{m0l7OAjPW_Ik7B%`_vu1znYnbhFyQ1eGx}vWopz zrA52bznd{h|BXhhzeHbb26IAtZ+RR z1;$pcFA~AUk%yw-Nj@ z)X%hEGqpNs3`7UGMh>tB;u0%dhDtG5#NBpu5+WaY8_y?x#Gk}aaEru5vuEUR!{AQu zH?IArt}70SY>WJmV9td@+))#b16qa~+PG&?V0qe$E;dlHZpl`nV8j~*z5r2X;u%@0 zib)XAcS0cECp=%6OQ{ecH|47UK;dTADu^{djy27+T6wg~dML=F`a*@>XPvYm_lu+-?&oxYjIsOcC2JKrb>)-1QTyc=w# zUhp3Ienje*zg%^pqn1#dmT(&zbE~yI+e`Q`NB5x%hTR}DtcDZlNL;@-$5G};*{?}U z?Sb`MQ1aK~lbXn)7dKaPkS_`XlesX&r#vhpPTBDIyqb72`g`y5amiuZs#qBu%MhX~ zx`c#qB2+V8DPzt=$cgbu3F>}nj(WOS{r+Zl5r6kxlorDsY>n4Q`Yi2yhk{6Y6hKo5ayJ$@>k^$?o(jhFk52jG33M}UqayRx z)EaIJj7Z^{05|G0^|MSA!ERUc^)#BKpQI~!XXrOF%DJNoNdNkZH_qz7qE!w9T;<6z zd7CFT_$(NEwJ!x(curh5cd=u+7oV`VYBe_|lk=IqbrJ(IrAn}ca=3-L@H2h_>aF&- zL8uAy5KqB>;0C=7id zt;AitE7vFH@*S{GirU&rBHZSW%lTjpk;>RGP>+*DY!03_jM;M;yfnk}(ZbVeFV z*u1v;Vo}L$fS24IPzw3RM4D1oysJ`9h<9H?x+m}}RFjM)aZ5@V3XF1Uo~Ui>s!kH$ zO+->G5pszuW8fO4!w%BdFjr>_RGi3mws5zd8ag5)cZLpT7pJ- zd^jUSHikyj#}`O6FPl>ulakDXyW8h!oULquUjnos4d6D9E<#%#)P#!2MUEJ_Hi^jPuUPerF^COI0t>FuzVkl2Wu|23WbF#? z;oFl#jPh4L7qyCRE*-`6H~OtqD!;w-q0f(b1kilWzR@wcTWWS_eW;(h8X1UkA>#kG@o5mMRydr` zGcKVzs9Z&%`0o20?_BVy=t_kdoUPE+I5EwQeD2p66=1k8sp*6h#(_W$Ew>2|kEN0o z>$dirsVMPHH62;lJbjm!3Kv!pHIP_bmNe~!Aa*El2j+DpZW%Uy#z5ASb?Kik?d25a zf)?|$h=hB=rBd}n&L!4Xyy?WdbAed^Y0QDwk*l=HTFU(#MVo zJW-qD*1-hd*;zZsii@ILQYRL_D?|9OlaQoB%tF;93n4wZ_=0GzfRDitur0dM7|*hI zn+m;F3H|6`0t2MS;Wes`SJ(=}Iibei+B>_rZ|+1KMD1$fkX0yuc4|v&q1S{&COab1 zzLgJer3Qu>vED6IF%!U#2D+^4dz7KDC6_4I;gV&OvK)8^$i9eKz?gZ9OkN4_J^xI= zT|)B7#Wrs$rHB1?`dq{Fghmp6;>jU?&M{caCsh7JM_lcpz55nbte5vESC+h#S>*Yz zz7XsJCFV78_?y{8<@#I10xjcTrW@e;Vo)}B`=Bavb%_>{0Z?j8&f{6V;)(*Ub0h=Y zjm634^)JSIHN4J7GjG-wy5CE-ur+OG7ttjR?T=d&i|*Nm9fdFp7iXh9QL7Dn8}?~4 zR!KNl>vCj3Rz#giPKn=X#qBGlJQdF-Z&rEOi(x>Z|XjI{N>4+7H5#Z^hv*3)!IZrasw2V^EC^n18 zq-6Wu3tfHFMvFkR;Q<-9Qh7}U?nI=)*6<0M%(iLFkHAFls@@OZtYYuq=5Ne70v0^2 zmg@#@yg}ZB*#hTn@~~jRyKnXImScekpW^EdM=}U67&ZsF&b33?ed3N^NW$y#-9v3{ z`P4KH92a;?jXlNTHq*PcJY{2VUlr?t^hH6YBscT2Zs%s)_N#*Wy4JFck}&B3oec*F z056`B;H2Q+m^{mtNx&UHht%NK!ShGgN(^wfcIG?;re01YJwi$OM33H`Ct#5&!P%&S zekEVNfbno_{N(e&s{8m?fL7trf@4YGhco&C3Yv&k>gHA{mkhu%M_ez)r^1G=TSI=r zXb0IenXbND5lU{}UL3tL*2SYGGA=<-Be~fodx0&8LVemInf;e1(VMTLA{A+Y3Q9%f zk0g*I7j?SDjbpZu6NVR3Oz-1PL;7UgH-E4a_#B_I%RT|VYKiz;=xP6) z$ZyqZ0S56wi>y;`5?e3v?B@F+Q4)^o_$3xyQt>rqRnyi6x6Qp_9$eaMtEfjlY6rEQ z+dhMlEsly+WeYMN_Q(qy3!sdLyKenQY$4o3DjFj2_&O1;t$1x`!|I{>$PS2R+k(jz z;&C-wK)C(nP}(<+%qk&XE&i&=$CP<*ySL-NiEB0W2hro!ntS%dMUQX}OKperb9@J( zPi*9&j`}2!$i}H8723lb>zxZqt7 zY!-*dFROcJR(9cg)Ji9d^zFW%l2P!lk$CNKa^tv{!BxMEJua2@@s4GVs8K{rMUu94 z-Ll(Jln-%!N0B9$m4D4xRe4|nX$uX`Kn8M7Sc#1ykcD?`D7;!}xxp}6@q%&*E5i7{ zdQhqjdk_$~$twH*l+T`GRck6P2HNGeJqyE@%J>k~r+GGwY2i?3jA;uay1lxNubU!# zgVQb(+NRg)Id3^tN5hk2+OPYrrTVseIwu zgY93MOJd)Ni^##CsvS_XadsWJ2@AID!8#;WU6zPiwdQYDZvy)!}ocK6oZQWP$` zhvsfF-85q|)_1_WIx%^d;uZ}ZNUG7y;Iw|yrd34Gt_-J@(ceq%%y%=$m`r=o^nJDg ztbYR9Sov6Dl2vjIVYpXWrUkbt?g+yZR0IosERC+m@6WI*VfyfCZCPwj8PUbX8d#Y< z{#6<1!ohTDBK7tx+LT7U{rAgJ+Y}$e=S+Er668*gMCmDxKg-2NVUiGFgpr5jc6y&_=M<2oT(;)|fi49=^~NoPD>+QGF_f31W%|T<4mkG}f@6BpmYZmw5J+Ikhj_ycLgZmf3m|Qav%}zKk4)mgP3`Q3udqBAvz}EZzO`+`PSMHl ziAW28l7Fq^qd3r9O7F#>$C0Lhk@vo`{9+a(mlG?m#s0q!EM{5;|Gqq639<2Y;v zi?dH4v^$MntSY$8j^=zO%uQ^MWTJQsGBtfz?3##2#a#u~F6SFer~FRycu0@x0%R z<%o?;yJ7n&;JwDD|C#$po*UziCiyLac^=itOey?x5i7ef^&o>u2G8Nje2i)!)~58}DL(Y#=JhE=XJJ#h5|)5%_slPqD`_QiWU6OW;4rsT%FFGc+n zST;n}061|i9@f6GsBtas1iWo_@(|gD?=99W)Hm@BgEXd{QC6&9U0mEiTn!aylQPM# zQCM*)s1Q!RFJ`Z(rcVvogeBH3d||a?DNJ zukm?(1svokp>tua&PbC7`Eg`YH|Og9-dTrQ!aLH$0MrPE6(dxDA7AUaT2D=d*z_^aCIGPQE`Jz*Z~! z3wyp%plZ=`Yi-)gHYojFDce*S{n>Kp?r7T&5YFYpfzpIt&$WXUTsoi2-lbZg`ydyA zSpE0h!S{MkovE3Uk$?FX9O^CD4cW?Rm5zn)HQ_ECT?M*I+(jq-!1CC?U7w~=46l*g z_|RAOqbzCpeJwGnb-TfVMIa2G5AI#~ARE?bM%{!pG$$h?GUjHw@CEkFl|)7I+6iYL z>BAP0r$EP83=g*@d*jj1N(*tL6FKtCt_x|%WVacgorgYUf_l3f*^EV_)?L{YitLHC zX^d}*z^Zz?PvB**Pg~YCPh=Lxt7BP=m1sU-7Lp0c>LgG(OFf0aX33f}jyqCVX-=dh zI9+YB3F!v|Q}W&jaJ}UIIK6h_+$o@Ds?UxkQ{&a-RawUAZ?3X8p6v_BmRllCHe5_C z)xR8kI`;~fY8YY2;d{bQ{ZrjjXGRJRXCPMBRV6(8E_7t{m_wZJw-TlKUzgyzL%TZj z9BVF|a(i)eP9G133hG!OIscH#t&J@3B7$Vn($abgiu+8|HF<~Mrz^k;yu8x`@a~%} zh*o4o)%lU<-ji{!*D}g3tm-s%Fy}eY&z|Rf)JEmzMlUSvHa;wtNenf^tX#J8Pjj|$ z@>%f7^q3@5*On>?mRUOYOy5KyBgxlLsR}*~owa8$7&!Hci%+uQi?4{wZXwG58El`( zq$Wp;ZJm&y$X)PCC3O6aV`MZno)6CAObY(Q`ZeO{*S^^S$Mk7Yh=5?Wvi7M1DR_j6 zS4_$lFn?WY(s~fvuJz`evQ)jan49wuI6x`=HZ-?jz&3%zsW+}fRh&5jkH@!hMsh{b zm`$U%&ndTI9P&(9W->9j%bH2nbjQ&^Y%qwSWK0BP*mSgi%GK@w#WGgt&%bQ7x-XD0 zj%`y712h+1ou~ecQ4h>#*r(Q#S50%2LxmBc;ya3`zy!+LBUNXt5HZ92U7z z`gKgV!}WQY#W8f53~L}o3V*gffqvrx>s7W_A%q#?5~JUw1?;>)QeDYn!Lq+cTC-kM zYclTE1$!6F+;-4K2Il}JeR);gV)*elsI$2iN}aOExa3?|okG}6V!S~Oq-5}R&my(S>DkLV%wg$5u*%Z;#=^(pX5 zzT;0#3Y~NxV9t*hEBZ{6b#ptZZJQStn(`G_S6F~yi+IBZM{g{*CQihrU}vtbIs#l= zsC^;gV>|oR0}!8GTzJhunW7+h{7my=4d2DWg5kQkOhi*Y{?ZK3$*3|w))+rwYvf2L zQ!jCzm!Y)Z1i3g(oq&gnk$%u6DmW0a`E9HH0z7DBs|s`=(XMJ^euI4RJGl-PFo{X3 zQJxgap!K%*9Z|a-8&jrdFUYGa-Q$259H!D-=h~ilEo|14>wmsOuQ=Zd#6C6xH$>xP!LhEdC${ugXGkz_cJOF{#DkDiZU|Ib7^l4m^Ya&PHhJU5r zIQ<1Dz`+sJQQfZYwNTErQhjoSdsUiJY>O{!zZ-?6ol(7K`TuM02ipxRYb)2t;8Ja3;xI*7NpUjaY4Y>bRo#6~_F zk6)taiuDdHF^;yCSrH`x8b2KovGa?J{rS?(@ol`?#X5|n8S>I|-idf|XigpZ2=QDh zW2#bFwq(N5|B2?Ou#D-qKS6EzY}=b=rup>wv~+S>t(QYoUEMndos;zC1f0U^B(1 zD--El=W9(-Wbxu}IK`L|ceCYm5fEHX@d(v_qoM6oOeoAQ7%mJ?-yjec=LLW#43d`QSoCV=^7_( z>jBBc&!7Jf0IWb$zny8Ka%YlI`tsZF`G%dcuV`zH@1b(@Fe+%Cnl{oAr`ZNyf{?QM zm~%Z+9ZfII^Od5a9JK_L%)L*kauQM#4Jmfc>=M(?N7R&Cq_AM?xQ;%zE5xcu`iTY` zIy&FysrZ|$n^pZ?RSZQtgHoMfJ~zCi%WbFWwK7cIv+*vmV_Fr@BM?%pR?u{c175Ab z5O2H0YVMZf^$HXf`G+s*m|IHQP3IqT@}W)^iilEb8)YNIFivz!kp@n>X;O(jT3k0J zq^+XrJJD!sMN0Xazua1yp1Wx(AwMY*=QrrSl@!tQ&@d7BQYItjKu*2aDM?1DZCgJ6`fWUWJt}Cm1@7zkDY!<-#eyYk)A!yy66|;Bd4xtc}zEDq4sF~zbWB?!nD=o`ao@53c zTj@mCxlEB@`*lYz3o>)w`A1pV9n+rKeA%`$EZ^w0IB7k0=gUa0LDUvfjne*o2haRc zY~LA^g_{>W!TVTp3of_1(S8~+HgkGjrji@~!5eOxVfj*G<$)6|^Q8j;Grw%7U4wq* zK~r9Uo!So~ZJp#RXF~Y7nPSe(n)k|=BO{KAf|lI+^?4Ax*DDn6*jW%$7oezIIpmI% zW=1kfuzZDc&0s{AeICfM-u^%9zaxJ8Subwc*R|8uZY7S-2`QzM$}*)Sw3Ql<&c%*h zx!Bdr#nfcOtq5R)o)mlk?10KiLgmuesXSLDD`+}%+6hS=7a}|Iq;xh>_Z|6^s`B)a z>Y$nD67hRHc8Pf8p{*rLZ5<)yl`{4DOnpqNMv*Bg<)cS^PAV46&;Q|1FG(!Ca@NL0 zRcGdFyIJ+Oe^;U>jFTT6CW2wp$Z?&bx%m`~qP zR@6x4J`LN>!RPM`<9dvz$lMzVUs8X=drKBfZ9Hc*&HKJ{NvQMybl` z!)I&46m?A;g1cVuGpg9{2sYij&w*n3W)n)Q4w|$Cn+?3Z1+DmxbeV$@M6aSX9W0T~ zNFt?-^`CiJD3RnVm55P3kN%k?iHHwkcO$ z{@&er+Ba19WvS#-J4J^KEa*2@aIr2P6BgMp(Ou{`&*8bA|&XY9DY)YkIPgH1J%7#pK4u zH}P^4OpU>vr~lT$z!c<^_E%|NR@K*49ak02&->L@GmUjdt8l-WFot3t{FSl5E+#GtSZYW4WSJmAO6@#FeaX^^#CD`cYhSGqhpSjhuC*+hgfo zm5o0qquc^Y6^B=-R-(Z?y;dVhvXIv4zUd$*IW5AJJ>3h_8Vv?8B_c^ExA*dk*7?SY zn%~tcrc;weVvG$dh>(V1i1O_biISruu_XIUGUrcxrC;U5Yx%kN!7R*^%kDmyzM44~ z=Cr-HOt^?)J+-QfO1Y_S$t0o3!la{(&1y^LJdzxe-a44mpx&P=y%o2Pu3rE(^MX*!K9-3ovdw7?;|baNpTZo9i?-~QkoJzI=*TjpV~iY`IE&@ zAG*6Bt_mWGmRW1e9mqv+$R6g?#R(pb_bVNyLoyD~B+m*f5 zDow3DOuUn`P$9}XoyFHi?N|EPB_%T2YBdWYq*dCZRi9Rt(oXc=^yjK;|3TcpD2wiK z$#fQt(&JTHm^Fos{!9I$tnMgdsS)8V2eQ)U-2Fa&J{qX)^h$eSxtuLYA7ld-tRtaZ zGcFx7>_X^cIBg%wF7vWJf=T;iRU+!#y6K5yGTj=b5$l(xR#C2(S+cPC>t<1YxD1ac zi5Y99GDb|Z>U`a?`+oIC0~z#Gz2%VQE7D!9xYsO`$vyMn)=b>6e#Vniy5^dLr`bKR zd*pow<*UJ;JIj~kTC-Vn9_{1LMzR59#_l&QQ|k*W#Y^6Dr2Cu6O=Xf1*Pw07^SyL& z!|C3JJe>E@Gb(5G>SUp+`ZC^6>U7#^bkD_i^`3k0Vgmx{@892VgEU*?_q0L#vLL&t z@B93VFKTNQ9e2&rv6Fihlc_+9*m(Ux((jnw-t%$E0Y)Gd!XwfBi)*8`W;KQ`6lccJ3`TDh0CD*{zYr+fj`_Iy6gR=Ky7 znHN~8Y5SZ4IA~xigqL&j z)8CB6m@-zm@t@?9QC>Djs3@p}qSU>HCQX&fBywN7NSUDioM}B)y>ll}R2+ZjoeGmM1F%x#wkNnR2$=uZ?u4 z^T;*AOeXuZ-6PALQi7|jxt9S`V&(El@t-&EGSTFu1d``W63U&MyYqR}KjqUZD+IL$ z+OLK5Q&+W4S7OrOQ}%VMF|~?2;lwnJ(AW6c!}q%5b(sZ~3jVCAtn!?spX~E(<{_xg zy9wl>4uFu>Vt;iMG0xFDSi#{>CT8_PrMIph27W=`6ahAQclw)_NjYRKCkET+26_ zpGJO(3paD+Y%a20DGJ*?@^bzK*GGg@s1ckR8KUgAZa~AkqC&wZbxh6uh6b|2(x_;X z&c8h+Nv3p=9-^FcPxd@Hq-{=KeC3QZ`uol4ew!ixd3cU0)#9XkcKV+=J15Uo=^4{G^x@BoB(=;l z%>!{1l$JYJrrs$womcC#yY7KQoxm3FFEI{y)HY>Dp0wY1AY zR|ksBs!o9~GI@38)SP14zGqfa8c>p?k78P(^tYryrnD_kR)dlU5-C4|mn?`>T1zI8 zRc6uTLmC>mkWJ3}`X~7!nJ6Dwmvrb-$;euF;G~HSkCrHY`|99o^LPK%pP7$$9k$fY zU>F@!8^KLc^cpwrY_ipW!VE*)PqDr$Px`V_S+JlWZDmz{XEadE@&>b%hH|veSh0l+ zq&W6XtHc$bT^9zRWGQulP3eLP{#v>4TD3f1|F!9M@tPz;J`HwC+ZmEMjC5&>kCr>E z8f@vb$ui16Bq5bEtEa}zcYIIWH!W>&TX9c|r)}UFuM_6Jv*aG5{c&%3pK4>Is**BNZMIna=)T*fVg3q<-q2A5r;0Wa%qSy0;RPqg089E3a)Ez>4ygc*NZ& zkUdI|>yQQ)o21V8=7L4ZbLkNorYz(A{QYo05)D1Sx>G5e^)Hr88>wVO&HtoDIApKh z|5-fzbU~1_-69|UQF3LH=-Mps)U@f!5B>xTD2#Mu-9Vg6HF;fAG9JjJ@r|CHjDlR1 z%geui;XlRmPyXFRo{O$&UjnAAWsY0ActSk7WhPn>QRnGHe|d^H_q~5tn!c~HVDhPV zu1i`)UWtqvQqD9@d0(6g*lXOi;Wi<30I&?QUS9h(dPb7Z5k>tb{l4;Z*Op#fOxuH$ zc4Y3RSLEoER*S2?xK>>AF^;2t>PnTJzlYA<5 zg3J`_uUAo7<=oo-a;MUTDDY0A@cX$$VY~g>ue3jOOLDFfqN#NeXDZ13jIEV)csrpi z3rZW>nwE4$J$!5jt0d5 z+ivUUXjXSpB%viubiHpIGv_Ou+w|5Pyh!}urd`hWSBPUzT_vu#Xq}f5%UlG$ebRPG z)6DljBsXP?VfWo8#UlkVmAWjQ3cxQ5vij=R|DO1#zrQM4xr$4MrF~q^R=Oe($s}tk zk=HcHICZ7tzNBCN`;Uqx%lEYsTgATJ7G=reI#wpD!R5@{J7}fUTy%aT^QHUTQw}r7 z=T6#--v?099*yHomja$>1SDmpRn#|(i8yp@4v>{ij=s|U(^CA~<>!kZ{P-Jfmlv(l zFztk_wpyZ8f1mWGy7mtAQ6HIF-OwTOqr!V3m_ zX_rV6g-grC!rE2O@H^MvFTP!TI>oo$@!!7g{%T9<2n|r%$(0O^l~e>FaW5Fogv(`> zbl5_)l8)N6y)V0rNh>8~$7P$iOj8!*aU|33%o4GBFQ?9)CJegnjpRGIju9^YjV_25;@FMK(fv`co?jtqY~UC`;(1$f;LoKnGQOf6*Hbz z4vQx6Y2UI1l(kQ6zDZX23Gwx%X!+Bs+whBUB!eCq842Y4UcoNaG1H0cS`tzIq-NadF z&2Bz~)_pi%5XLX^l9ZM7sxE9`?w;ncZ$5@S+xo#dru1PcjR~s%m;bE;o^BA)hKhB8 zTR}(Sdxw3Oymsuq>e|0AX_i(^GqkEqb$@d!!UsP5M)9(D9%r1kMddw)m7)DKmu!D; zmpNb37oC1+q(~4R3lE^G(0Eh9id+hi=s^d;<*J5SnyCDy4m`h|KJzpT&P&FNxm%GachNPxU5o-VM4~p5MBDSCP6KdM5)9(o9)3Q%qJMw#ibYTSxgwHGiu09= zl?P3URmCUu;T%drDnulgME94ob?Ng+(SU+!Dpn}W<6t8nB$lg4wu_#&{WDL>v)otG z^?AUKiNsfB^#w{Ich|Mb0K%8`l0^+G9j3T6mfiQm`)(J1`Kh;d-2c_}p{W}{Y8};| zpZxrC@w12S5f3b$V6tYp32ut-DKDvsaMg)aPVMV|{ayR~ym~@?V0Eiy&|xWEz$CQo zz9h2r$k(kD-}~|nev4#Lqv5z%oU|N;FN@KZ6kB$1tAi?t>1|@eSI!Zqo&2#9k!(dg zQxX1FKBZ@!^QYoR_ut_|=s7vC&hJ(N%6A0(zDNt%N8z$4L*BqDCF&GLLq}4*a+Zub zqL|!#@cg6AZ@m;BHK1B%il!I+u{r7K2|ty%ZvBkEmhO8!5d-vu6l?FJue4&)kE(!QlfC&b!c?DRzJ1*bemeCP8& zu>PldnO7NPxD;t~8tqc)e33W74juR8>BQ?|$#A#fA;Hi%nBus;%m&7(yCp zuSV+U5y9YErQiCjb!#xbq>PMc0_dNjlBKEpNG3{_ZGdz=$%$`5T0<$x$eQ5yDp^T} zIU!Y2Ex31jX!5CoTZ`!|Gd9TS+US1_f}3Q&ZcSDa(2|=ICz;G9PL@0)yf4_fuC5t^ zMUmdA2!Cz|$MlYbYv#Tlm-3Y-k~%zJL_$sanXzKYZ18obG?m`UVy)uE1|pGrvyOl! zk3vlDbAmYIX;+GWx#DJX-mOcXsH4EF3zQTktyW1D(h1;mjaQQ=NAPLDuX28_u!Pp# zOHLZ5dG4$Gufh^iPYei$Uh!wgi_Jg3 zM;vj~YVqDbyC{0DT=+ii59_vl_xoQpzx8yzo+?J;7_dl7K;>?@6y?hW0D8Ga zHYmzNS!Hf8^t?A79xT-KOk^C4+-j}+ah=j%aF)_eiD@UtacgNO?Y?T!8E6u?Wm|dV zKC|y4W6}KKCr=Sm8!bV7%V{64C7@}g(|Fg}e{6{8#z~j{q_FyTH88$1UBqf9mfy|3 zQ`Tsx&IW65-07{PLuFN*C!ZKPE9nsN!@j307s7*C7)aaTw##hx*h<=+bjo)zv*{A? zwe|P-zn`}CesTNKy}SPmWp!JxSD&K&FF5%*;yYjXL5m08x&hY#L7K2`*`CL~$?UY< zpYbH|;|K0Eu4vER>nY}dv)*w*OJbV#m6v||bEc2Hr(supk`q!i*iv0OXh~aEtNKQs zugaOyN{Pyih5`qrx)wWXQ!>~x$KDI zYscP;%+&t7&i;L||Nc*HdyjgVHXYe-Qkzoc7CG1z-D*==>HdNoUaZ3=MXWcfE9JL7 zYYFzzxu@&abU8Qkatw5+s5?keT65&G@$shZO%1Z6Hb-$SL#~bOJ5$M@YpB$XRYO&a@jOxVn~-$JMeW;*@%8q9+`;brtI}{rf(`(z8K-tR>3Uv zk;lLJQ0HF20@P$sR@gPu6b+J|$`zXxlwyx16XMZryUaa@0HUBA;2wzh;ilV-1^4u~ zolx0Frq5Ut(FYb=d8m9!gymM9T$#CkK}Z)(D!Y_uuKe@P+&!CjGtaD{gyhPcdH^je zD$Kjr6qjFQ<1J1+^9XaCBDEVOS)UJ#9Vu3RiSp zO-LDG;8BmUM=X6=!ud}&?Msc1dlz=x$@DMkwE{XRoyA4RSxJ3^Jp5MDN~;CwBI;>Jtx>7+!Ex;I zSTS@?1UGXl3sGI6`b=f0C2lm#n%_n<(*{H}h*U^>u3uw4qjaroj;;T>S;0sNA~Pf< z*%>JecEmlNwWE}q`>D(InB=EbLYKV%(U#+zq3)i`~|-@^cGT*bcz-l zFiVaKuYGCsE^}3TzG*Lf(3%J<`(;5dlvdel7XL}XB&B2)KO5(9rq467My@OlJ!Fx% z?&sT_eyS+Q=wag0PhVSnt`jGmahUhyRsNnPY7bjsL6Q%=BDZkFhvre+?D z8B%zuCnLVAiK+;`zBY&|=-}#iUO(?kKVyaRUtADUqmS9Ke9Thy?GRHO&S zCq?op$&yZ5C|M({++?pCB%rD-wAB(A<;==t<(EnJhjNUREi*2Wd=2@~oo$L_FgKAf&h2+LM5w!K9Zz zaJkt&vG)mLX5+V_Z^;y|RLVve z7Os z0V@8{BwXWIPe?{^bt>|unADEq`65{&(w7`axy`<4bC>s=J(E1q7v=j8Shj}= za4PL9K07yk(`?&W5K#T0i2I!d(aa-F()c_|+niHecjAf1i^iTW5{ed7|dY-sNH=l+_c5t}o$2Ya4s=CO`z9-{H}=Nq56%G|Tj?e=L? z`pqC2xXaIu4*k% znuL-^Wh&QVzk&o+m6alx8kl)O#@6CvPhA}mU!A1!BTYrL**$w-PE~b1+0uv_X^AF` zbnP#8n01(g?xpgBPsK*Dr2&Uual^_+jf~||jgFO6dEs>tEF>bfl#wsnkefRDpQapa zdSUSjCbcAj&Zrk!=OW=kIN7HV*y-CKc09L|@?!Oz5J3P_?8MUw-wSho}WRFHYp2DPHAaU zoq)EU(z!+h`oIZs!_7@&UN!#X#W{LbO-l!U>vK00zgIeqRJTsNW!avX8jI<4h>K7} zTwOn4wLo*Ht1V4hd2ahit#PX51Di7RL%AcSOP5TTpehPh^5ovhI%S$LGQTl;R(bBk zp>rEp#q*W>d}U^z&V`@0F9@mEHqCMqG(}QcL{iPQD^{Zd#@JGtt_)Jmj;gJmL~dy6 zp7c6fGuw9iRLwRO5l?FYmBs?PoBz%dOKmxYx~cuPi&7~aO}V!67$g5Qn_H|U`@wRl zDig6kw6&CD?TtGE8BQC2)uuBp_Fw$f&8YP~sarMErKR^x4T+U>XbqP=%AaiAE=rNi zd~geQm@kh!btI%!h7Ef8;GM4mrJ{xC6q~6{XL97M3UfAu z)EV17a(tDdy%7xl*WjN?WOT#zKERb@P4VDUWW9b!0^t(1%s` zL^PYo=hjvoG|AGo2WVk^+fUvg;)%Uj`+8y`3kz?g*A#5^F5bwvgQy=gaTANJf2jFh z9NYq|rJdauyC2%;ugw?8aVr+keX|Ku{|t$cp77?wqg4!PmhYHnPWd_`6i*98bSy2U zb8j5DAXyv;q@0G5p3c_O6M7n-ru5lCQJPX#?Q7L2$~H}ASzJjaiOV#+s!G7GMYgU; z1oG*aRW7ipE?p^P`?fxj!7}n8m0ET|qDo(P-Hki_A?pfay0X|NQxz;Zt3F`3t)wi^ zqu@(g5}+u*r13ifD`{`6r1L0y3O!Ll(6>s$`=%M^VvyUb>&WZBzJ8l`-lQp9{gVD-`;5qR>t|Rb znh*M60_@(3suvY#3i0%9_laFD@5>&xx~F$Pet&17lwP{99P}nadAM}fte7@!wDteg z_t*3*K3#s%^~REDrN3C(lxb;Iwe3FFn@K6+|Liv5jtTEa2y9X&z{o!LAZ_K!qPS-* zN#1WA1Vnws*LL?0{dFQ8D3$jSTkwCHh z`UZ@omy}2(t6Y_0)9KW9Wt0I$`I6>-sAA{_Su!~)UC~(1{l3s!rQNBFrtp2Ft&Dl8 zN=R+gIeA?~Wv;K65T#D(hN1z~Yg^M&sG)&Mh_Q-OKk+rYi@!VnuAzK4wTwtg7WC)A z2Ok{z{2ECiktY$cA#g&fKo&0f_bq67hiOQjvCf((fD_2%5yWP>Ml)R+NK)pakA-jw zLb+SAkwr9{bKR^c$u+baL94 zQA_@iJW`e16s-oO&oOd7E?;`dV|}h(e$u}4nI)}GSoxfw#k|Zrb6|x(o1&FL1}oO3m+l?POh8g58&0NFQFG$nTPu+j233@{T_K7;&#BU<7^5D|m8(ENZA)yG>0md@WN!6KiO6Emw z1}fWlyuW1udQsCfCAT78N^G!|!D=hhm$@#zSRzVBwg@Iq#nX15E1c-BwgMXq zslR9G38{$4u+8JIi>*o5` zE2C<}ACY_p!Xmx)VX%4uL)QsNB7j+B;mP~}BTHm$WLb~4^tbS$>Cy?edjinzd=h|X z0_W1dOQGfSM2iWmbCG#VNV1YtlBDffxVNk#PoB_Z;bVqhrRNpot|*^GO5*!U(vu+{ zUhqH59N}iqEnR-P5%Lg(?cF*4d_G{1UaOSyeZ~E|ReC%5YZKYyWSBjZXxVGpUVN`P zc-q~&%Tuwf4Hf=IpJp9NVbuXXG57v2ZD{|4Ki zNq%nTh-c>W8`92P8A?Z*ZQ5FkmHPRYy!EK${LI}udtMFcNOcyKd21d5VETTZc+u%= zOr_T^D_KqJB%_9kkhrujWn@~D?DUeWYL*cF?WwI|=Zqa)YGSER{Fz!(bD@g!C$|*m z=f;BaOu5Z$`+s6L(aLFI(=T^K%cpj_yy?h}PDh==fq{-xQK`BbD_fVRUxrc4;-vCW zx?~^d>^*9;n5b;EL6##}>+)1-#86#-|7GcUwp%P!&i-1(u}@p}7$F{fr2AD^+IIQ6 zpKp(z&r1sur}2$XUTsA7k2`gB%}b=}FI?|8HY-0aS@+N@_u9n&t;n|q>5!UPB6jHN z6;sBdUiOlcE(kQvWO+e|asbr0PUnveDeXu^zZ4xLqu;f$N|NLtlp&^i8axnF#T>&c z!aQOx{WxJZC$DPO6jn*3Po&kCMA9o3g?{O$gRhjfjE112uu$jf<~19l`w97fVDTOtiQ^0FA^0h(>xegg%PRfQq(Gq z4P92HECn-Jd7$+DUqCvg3kce;F=LvNIYqS7YH==tn?>J5vOP8$o&_tpwnwpZa~27g zM%W7;p)W#vXY-Y@U>kQgn8; zKd0#^iepbW<8X1w1>g6}aT>Qbx3s5l?@OsHjKV{rI6!&Kav$aH-$i$>S?Me1eP|v6 zjm-1Pe7=HO0iCN%zW(i#SNeKl0-8!{2g(F`16(?X@^e2ypgDsiuttVg>geq z$6tP-4P-k0^fj?m6_ZyYD`XI{X3pihp~~#^UX|9A_a!aqf>H-WQ#RJ&zC@pqUxzz$(@_UK|A}J#zu!M}?_#sr41SuvV^`vqTW%2t9B{yJ z*Q2DIQX%xpNNr$f+Q2*|iB#8ey&{h-Rg>om__UC_Kj?>mtnr$S*vwcro5RsCldnSvd37!+oV#{Q$a&LuIOfQ*& z@|;{$vS!@@Y1_&jUtn=j<2&+lciJ{LY*fIL}0E6q;#G{)fq$mS35_Yd`s7!LtsDN;{QmF9|A~0U{a+PXv#7jHC4QPO7BX4)K9#z9-t%82uDtU9nytGn zdxhA1=f6bhuf1_567*UKSj(iah8nVdK$0GK&7;31j@bRjXl#b2=<5BrqfkjExKYvw z_Oe0k+Nc^INGW5VLf(!@RoUjIa(ki8NH1llS;N{LAv7}bq?KH|L{>Z3%J{cVZ*ns8 zmc2m!9I?u!x6Y*z-c7g!8CJ5Wb-RDfiYe2Uspz>&aqOw9Oy0C*l3OQ# z@0691#F(Gnr+`TnzoXt@B9qlTW%M$~5`;1o=_MCj8@-NNeI|26+)JUkv`HEm`e5H=}o{d?S#yo4!qDvP3U37D<~n3DO%uVfONK z3#1ZdIjP_&s^V)V`O>>9Mg0W@U#U`*v@kv~)3JDUDHedY0-<4Ew|!Btj8r_+B?SrH ze8<1|zqkDV?7az~Wkq%Gz1BW=>f22-BO-$gJ%Nb6C_Mo(IG~6F=6xnFiRMc_BT>L*~=j=MWYS*s%*Q&LCYx`AtK;Ewqlys~goFgr4(UUy)=nD$r`F(GB`T5Vk zt5@wLPPwm?6Z{^b6}w9?=z#O7-MV!vELgB$+VC)n1x(gc&*~q*V)nU^7 zedvtR)9T)NHK}aWbKPXL$w0C(?RyonD0*?9F^EgM6XI}FU@dNSRGx#GW#zItQ`1G; zdroAQYYQun%uildCa((^MZjD~z+gFl=)9;i`D0=Ra?zfF&nyHMCB&~gch`YAEbi-W zZHleQXzcRqHQ21cb4^_ox3Q|yhi87S@{#+l-HNt4p}VVM<%sZ+)8-{tkC)s#YPPW| zz&zV>Q-AG(m1q9GdaPKDT(Z!#3n(8QZ&;=#8{g`UgO+6qHo888H&KK>ovP|^?blYr z_1|1CK9?f+mG@0GKDRvT-W|qZn_J9iR#YWeo;@h5c$4#K4?&%M`iPkb4r0BY%q>Q!qRHquMAO@G4{68 z(yGwuJ|`YyOXj&g&pZa42L#_%Cr~+u^e0!8aa2YO2ZwpTf`ou|ae+*3iwZfg7=vGe zN+c3+{8XOSQy^W67f6Hxvr@Pg*}dbcFc}KYXjmDOkTK`8g{S@JhC-Z@BYnxrBhXv9 zj)-)1M~69qeFMeORkH*BJ`%z%*s_?F!0F6er6WqG+r6_$A-%my-g1<;F;jjFa@)<$ zSJJaYJ+dehi$A^HijrgMd{5E$5%hvYiwWyP8v2Yu@@VyC8KgQe$z4|#u8VKWgXNTZ zY>`Hq=a!LLw{;4*CNCyPU}Y*WJ<;$zbGs$(IHnoHA-O{bY}$H!?hp1)TY@Y8SoI{h zw5S6#JRl}hLNh9Gk1E{xMsNP zuj%p3SZ-G?nWNnn)@>SLxF#zc>o#Sl9k<;s;}322BtN$)hR@2PQPK`H+`>y;=U)Qq5y_!XC>vV2{C22jur@Uma1{C6&ro-G=ApEPqSowERKC4*ePyf>@cDB87sHT zi;fTiR$`nnVhaA9NLaykE!?8qB@~IXHhG@0iaF6?u`i!lX%IlRI1XE-jL?iSIf}?8 zbP=|?8^=p*iblN+aDyEw8Yjq=1+_KN0=N4TNcOVo)Y?tZ%@{ykh#F%Fy|p_ zM9wQ-wzx-&whi~#MU3+~XD$h3L9NwX!T<$7xa?*xR3~zrf6-}rcTWrDt}ZP^&Bf=w z-@5Jg6*e+zY(&n(YuDjk5gk5H~=&9QEH zSuyD=`9%6477Um+g)9h)-%l0MGQeY-LQoSUh^S~Rhj=WszWIYw{i*f$2+V|mMU z02L3Cbc2vb7=ida9)J?(m=8E8TL!9fkY#$1Y=aQA`HOs=fDuTPXj6{C%0WrgU>kHX zpErEldOVl2klJW`Mn&Q6i5@$~?o|#tN*`@96i$*s7J%mRw!Z12)3ud#WF&{)oaB%(3UKja{YAlzt>H{R`4DNT9QOw>GffDog zNe1q=OYh7?t7-=c#o2o$d=Un;QkBSYTlP_8oySb^w4+J=rXt}6f;9@L8bsMEuEV5r zfu{y2F#*tv+aDS9t5*}5s>Fcr{lEl+F4WmrctPM-{P@Lv%n~Rde=bPA-BE}4*@qcI zzEmFt%tvq~NC(_$KSbxVNK5u!WYPP7{pB-#w4~eWa~27~0L0+Sg{-|?`3NE9A#X3Y zNC?|~wn`D^#g$DdRNdl2<5U)R`+G*I4g;!1mhC=UU~pJl`|DPLd+1y>)^8mX_iE{a zF7K+5`8Gk%1a$4?%65yU5W&oZiU3822xsO;(mAHX_y;!f+CZVeqcE(OzR@;^Vi+tPY0jRroHHmBN^`%Z*H7rae0Ayc=pO^We1rJippP=f3$^V@W02kC zapTlc&pZS>4tS9tchE-aYwS}V^FC3JKSo$)ux8_sK|OO)tBHv)0Of)>`Ah3{L*RV!2sMig3AlC>}^mDfxTRrR5Q2`K`Ahu&{mfM9G zcmjgMMs<#kC~eA`Dke}rs+AYPeASE`sIOuqrxM#2O01A#=zWFcWI5?$LF-rfZbLw& zSfLDm#D!k*&yHt;!@M4t*{Uz35#)j*2nnCA4w%RS$pdvkM;^t(0<_QyG>FdK`Rs@Y zFc=+EaQc!S(QZ!o$17K0>rsJxQsuksEk03p4L>23Z)UI*VR-?gxY)H0?V-LLRl|IA zqw6NFs&7wa1u0`W0xz4xwxjy;mAu;~b$-ZlfnY5HmLurSAxj1Qja$rQ>$26k3OJvz z08or|E3+4HD-V6n>96PvzSH4YyKw|op4b;8suNjYeK;|)5b=JX0){AzkHI3ukvyLF znS(?L39OUyzMINoo%~4ZuPeag(FT=r#;LQe8f=pi3qk!JJuYSe6~ybz>zP|CpkH9- z)=-+sI_FiE)0ug2UT1ExT3V;&A^QC2T{~dRS}TuyW+&`C@JO2kfiYygAEwfR6Enp` zuhJ+fI%s>J7QpMaj93P0*flhIH4igs?$Atj{ME>);Ev)sq%_7Z=n270*4H(6pnF;~ zdE69=`y3YaX1(P7rB&`1Sy^s4rWphw9QxS!dZZ&tJIA=TgvxAAQ}}tUZ4FJX_|{6t zrq7woRd;on?VKa#*R>VZM5EWBVP>sys*Ei*)1=zCSy8Zg#7484({$2;34MC?IiL8z z&HDSNE<2;t1<0?90uJb?@@M{Qw>@uxSslBDX9BjW3!VKe_*p;O$FiWT#2qN0&j+2~u~w=;vAS)Y((CrzS9A}-@MsSGjL`ib}7 zR4r=Xf3p#p?D(q>-U@&Hl`}(=DvTJCGD2k?r5uEA{o9fC&cHiejzv9PaBm?ZYTc-< zQA-ze2kae6OdC(&=1CnaphM{h{}$wb zp((#m&I2`NqwqKN*TuIy6bK(5hj~E^Y2SE$W>>a`;ETnx3Me7QB9z#-FhRPBFAOkY z@GGr;L#;~#MBuMVw3jYFGuh<0n~>+>vF-m7VkQBJ^+A#R5(zzsH zGeA*gDGJc!^XAs03`;D>bw%5fdqBnp-M_fV2vTC%h72$WD^HvQe}2)8p>Fm*ee%-N zwY8Kiu%G$rS$={RFf{gTtS-c~i`HG#Q|pYn)9g5*hOi9`S91N(Cb{z0xIPCHJO6TeOOl_N+?RJA+QXXODSgbkY($aSlmgZbYA_xgl z74TiTFmdwh;$yK-C{U|~3|b=ER(V{R52C_c%r~{n;GP22p{_^g+-eAogTk6YLNQIy zv7R>3$2v_ATj&}e#P-wzA{u|vv6aYx?PUukNZFDUSe1wrVKS8ua-4OfWHUsZIIc$^ zpV()X%#JAkl&UwPG(6a{$YLnlnAfI?$Qd9`c!Te0XTi$kWZ6Z zzT@$2#t5Zj1ZEJVU=}#QIjz#Vz~5iaoWq2=_~69f?As|7>)K7DB_ZzG-0@)Pb3gmF zbIO*c;=8tz76%DhvZN;OgB8Kq3=a;e~v3A-4_g*K0!fuywAFy zxrNdDkF&nPt*3qg3l>NZ8N}G4fL-Fhqen>@;p!Gw7=1oUYZk{)@vkgo&OqcA(u|#F z1uBM-nA*TwOa;F%4U(l*&!pQqxR2jxh7QWNJ+gO!;`6ct6%$Ct|e#YkALaTdh{(y8q? zgyRbuIIiBldk!q^8xUJD&3@9_&BM_mr>EiVqW1@Dr?K2FwdXiMv-1}45u)B&)Hov) zS%Ow9=@ow?AJg?(1S|iZzxnFfCD#_`r|OQs{Igq16WPv32gs%XM~vh!r_Tt|&sssc z^pw+K{hhaUhMZ|2HykjX0O>@+-IAO8&iiH@s9Eic7XX+*XTJxHvU5|e@(L5KGb-`9 z%?hUoM^`mil!$gANKgBDTiAQ`(~Q$*eBE1uG&GZH&?M%yhYmW*1f!9))85G1VQ+-| z(I1!2t{r+Fj6L?_Qdx@OlvENyI9`C6D!Ho~e^2xQdDUeD!#jmJL6!P=d7e|ClGC$d z?biu#>WI?u6$3(Jwk0`DTc5wuyBY`><()NE#b*XoNf1MdquMklTorK6xR!Sut z`LUc%R8`kmK`OGJM|GDYt)&80i8fUp8>qO@c4fym!|??nkwR3E4k9*T#L5#ucO?fA z;S~Mnr`fx&&HsL3ShV7HHVM+yAp@gq7OrqGaK|tkk?oWJ+OI~ za}@$Icw~PZ9qpp;xd2|XaX4HdMci*3fzK48^Di#CF(E7g&VS!&S{Q3zL)&2FPwEcZ zzE=zx^~n$3=G*Xrr)&C}Nsyuyq#X~cX>2tu#3>2W(b2j_?rhus9Gvjt{k^#G(Zeb% zf;{dAfFYq+h8xVK&og@#&Ce0?$&OicUZyfJ_PGdVj&0H|EzC7aX%7Mu)vv5eKP`B)vog9xwMRywL4RR{+tX!aVIdx0o9=!T*`MV;9jd^0 zF|3p8+uWT@muX$Z(4whS9$!};(#<;j8Si5bL8St*fFl?y=k<;#oh7<++!YnFRgRJd zff7s9L32a4O&Qi{S6|Gk8FNfiOD)Ad$L)$&oyJ#yCH;mRJEbJZGzOe|go}rH2I0zm zQlp64I2zGizwoO}>Tu=xfV^^UvWZvXB-|)E+}l55t|8xKj~J&)MT-WuN=<^@8C)9@ zkZ^u~Z{OYLKUZ%7IjA)|x&O!uU~uQv#^ShXn9t@Wnlvt(edgLtCI~9mo^od5CJU)% z>_Nq#mRJMC=qqZ^wG2T;qb^|K8Kn02Xxn^8Ir1QF;Qqm7U;p*NoV2NPB_lp3_E55>o$1OEbR?jG{|YR4IMeQ4#9KEGve`hFh7 zEOUK1^Q11g;XjA$>$!MNI>#&(rOm8DO1YR4{E@Qot2VP%4Nt1{>No=#x27hoxGJ^l zkoZs)WBsdiv9PFCW^$^)N}&+N=!Lkbv2VL_(t!BB$uy%fpgmPlfn$a0T*Dt)(GNde z{TTcj`lU4!6QY}EA}DR^+m=#t0paR2u;VKIf)QxIgm#ZKvnynlBc%mtEHWuV-VbI` zRuUIDR$_@_j9PIP(?aNP9t#Tr%?=%gPZBbU1++Pf=ufU#3+G{(1=8D1>WN5aaDpn|uJ%03Ft1I=1GiGXprq9K02rEt zJ-Qe@oC;&iX~f#(>^A;#BJu`Nh!>@}AmP(RVDPD!H|icFw#SVkH$5v;VM(|u1~?7T zl+{>ijL=G)Wf~9k-m1zhtr-hXN9h*J^Lo1WwB50=MnKIg2Ge zYAhO1a$}blWv|~n3P1k30p7p^nGvx#;NIO>2efL=0 z+XEYi>O~(J(|yA9G2=fd&~*NxFM4F%rREKHyi8kYPj6^NXlS9Gc>Bk{y~~!BX*ZeW z#RAYoT{Bb={clljKBC(Bl!8gM%F$~xt-tfS&~`S}Ib-%L>84@E1CtfW_=4)!a#hV9h{}~T##TuzizKG%){XKt zF_W2F1wue%a3SLHMG0{(m_^aKv2`J?SGt`HRtVTIJA1T)aIT z*OLUM!#~CC#m>u^xOYs@=X>GOY%8E+=w{Iudj_=Ma#r)N)oh!*_MErDYhV4g&KT3N zlr}G5C)QUh8A8pEk4-;hQe5~fO{&=sNsD7p&0HV0T!9A3rkX!VD$nGbBvUl~DXaJN z!_vMzkYTHzkI%0J}7aBep@v zCBAGsEb*7++*NKqY|ETEC4$uUl_~>N%20yLuj=PFU8CRk$LGAGGq}taOKGcC)0=Kx z6~Ck6*Xqc5rBs8rC{PhvDOqGw(fJ^PhaigDRxn<9JUm-9uCfYO&+8JC3EXv6+yM{) zO%aBPB~z(xV|nueLn=mdF)UVitz6#vp}9WI-L(%P{92h{r~acZC^dix>hKt)>iXVx z*AP7Tw0xwD4=H#4m-(4Bx0GG4&ea^4`9IN(8UyKy0N%u+#Jwq`|#}zEXiZ zrarj{Af&)A|Fv;gFVg5|B7|I02)CK0P3OGgTJd|%&|E%Cp$g+#h`JAhmiaqx*Qkvx zl51ZOq<%io^~vGDom)aZa)}^xXskRBs5F(UmeM-SMqE^fQ<~IgDRxpB2^EXahGkcX z&b2xxcz9U7T`mjT)GCppl&2BR%|C2qT24_KqRH*H2?V|xs8sq>;~$hqx!7Ii3qZ*# z>;HGGU;lpe3&S9? zXZuy5bfqN2)ZxGQVgO`n+1u|PhORC&tUCzse`OI^jfD7aSVXmZ1L6V41HuZC&R{;c9rEV3@I>JU)q! zN#uW;GLcOeLFyJTbbS8SUAlgUJ#5mc9`w*w^Sm5#jA!F&Ut?<`_Bbe;ay!pE@#P&+ zI?n1tl}vwD99c<#su2<@7M&6>CE1=#(8jnYl_<(leNq-*eq9xU*RNg^R#}Bn&XZ`N z>bZLrcr4`XQ&y(W?~70ZekvyNVxjLHz5QgD%6g%sc{WNe!^K?6q6igv419e9bT&dl zS@DShV#@C&SxCFPvmn5gV%cz1lIiNB?3EF`%NKVujEG{ees){D0Yb5RVMS(^_F7O( zu&c6a)hbSd6w)x(t;P|8G zdv^!JoX!11t@6Mrb!fOeM?YbC&^(ow8;+^UY=qP_?H?G;6-Pe(AdDsE5WP6D_0)lJ zXblxPXZ+@!v8KV%k?c)&evu9mpRcRfo1cqQQV)E-+6bF`xhV`*_=N-#QOxphn;p<|b`8;qMvFwJzQB@**CLS2j_$g}NC?&V{g>}PjeIv?z>B2|IMO(W_$q0m8RkjO` z5y40Zo&p>8zYRi}OYFwJ9k_ghsY!IU%>RzW6 zwL4tM@JKX09P#vneu#bOpd%T%flyIscbypNWRmSSRf4pY_dIgwF@SaBsu1V{5L~D< zD=VMzOxsx{N~dCFAqG*!Bb<3urNaz4UqdVj1~>5^+WR{#eg1hbnb-sK82A*FKR3)&$~PUyOSwhB`pv_>9o*~MCzR#y_L3AGhjb*gfii;BTvrwn zM*$#^7}m3&T+e4Mw7!y@@I^!9dL z7y6~u1Ms1hbK4?Fr<&ntuui#OSd%~X+T!`qcq6KocCqQQcq0;IHS6MHnXEHhl#)Ls zFJ*AwD6~XL%kzY!DXvP3|JbA ztUJK-wr7aVxtLIWA3O9|IPCHJN`H5AsY60honQBww?ST4@YA3FTcJsfs6Y7NgW>6? zpKe~Uj0=Yz}pN@aX}+b-Ei)&jm|q#mw3vPf696H9auTeOYeY4cdL z6)!ssZvT(RI>XEJc)adC!|RG4h$FiTUIAjwRsv&xar# zFB@BU7RV*1R_h82Q7~KfZa2v-M8OAr&TvtRiFUFJX65>FE|De)6oRx~ z&&6|KhC%MyG)*fy1@nQ~ZBd>+V&;ReH&oA6a{TZ+dM;Q~G0dKQ-~ay6M)kL4%MU*zf zCsiuq>4_kCwu!2ODQ>#^C1X{c`9Nyl$-qNwM)7c^U= zk+UQcUP*aKH=EoL#T`k?WHphQ9xJ96<+uC&^AOz>Iq^z*f~P+)(!o0GJABEuy2%Rk z2m5zM*lB$HZ1XD%QQFvIeMzy9x!1b>EY)Z*C4_~t_#cm-V;H!2%uV&g_3PK~mAbz3 zmE*6vluI+6+i|A&zHCu9QJwe|2pM?*cY!;#PI)W7dM z@JOiH_vp5^$SBPxwZG>$eboH_`pE8a=hWQQA+yhhWi>n0l_6vWB$R>Z=jFvebfWNQ zwJ5E=`Kt2QXrmgY>oz5hBfOgy=oPQ+-u`{IF&`u>FCPDa8x7j^q>ywo+*7Jpm}3DPn!HqoA~b}^jrixGP^eCQ)j3>N=(i{-$0 z{e=FubYU;7+dK@LN9wSsr}5U**WcU8==6LaSG@1B@w*mANi87Z@=@{Vy7!T_mA}p{ z=vTb=G5;C`((vQ*udZ%sk^cURRz&`*>1|oJWgm}6ZlOs5D$YGYsWPhB^Edq}H5e`K zc;Zn1xu?yLe)6ABzfi7=eVzFT5fZ4l1q zP7yKnZ`c3 zMnML5L4iQj-!-xzEFwa1lyQ-$KYp!#Xa2;su9ZZC zkSvn*Jh%4@^nKnsfoxhE2S*Gsz}~CNia9N}| zs;`3vPxuFb)jKnO%E*!obdHWFtrSNN(G#|;kv&Z8AyjIw+es(2a$*;6C9`6%}vur?#Gm}~7C5aKoIHqCe+zXc(A!IQ_w4I(8f|k%aM8Ck| znz|@Z#5$-iUC?EOOAh{X9kxtw6VsM!@$))M1;{K{Q|wjP&vMu7IGkWfKjdR-Fl_dG zFxiP#F7DIY)%sk*Np*Gk>z)b6$|Zf~URZ>j+rF+_A6$LkYDK-#?2hP+S9zE_czg3f z0E_pm+v)_bSwPSnn^_LF(m&e;hHX#hA^;XiMxRMYsS7@Mmdy}Vhf`1J3b?7Rnn{;j zl)grDp3TBX_dCKiVa?pLth}>huDix;4AxzN<`>;ZLfJZ%s%BluIy+HqvN@TQycoM> zb&lCBN>!3V4-M!+SZPI@{+3T8Bx?Gh10NOn64(QG!8~9zQQ-c7La1B7J)KYG$V?WM zBzmh$r0=G{VZ@ZFSd0q15-$LmubKn!GnOg0c0gFkmoM27Y1snA3tr`!qVAGNkfv_G zTeGa&G9t0CV7Kg9y|wTY%uj%q*LK5*9mDB3F@MfyW0Lq3<_FxS#aIyP?z))unF)Ww zS)IDD79vf_a#pklaZo*%7FFQ;7GK*6adKQX{=?ErR;PAvZMCz!=~z~4<8f2_qBS`DIf6#>9RfvLs3aWd*yRbNN;xN|>I4$m!+Zhtq$*h$Ym~7vuHHIg`;g(B(ti|8r|+fXf&2Ef3kEQ0 zVBPMO0n}&S8c)U-&C<2G=XtW16-)Z;y{_v~j`~)2t;^r5%#_aVC2B$L26W#~l(KcU z_0j@6gL)>W{x}85OMCpW9B{(yzJEzYdhS5<2D6Z$NRoe-a zSM5Ivqhs`NS@Lm{1*qt6ttHZIk1%h?p)I5hK6#zBkjis<#=WKwubcWP|%rPRVm}HaAD0EX=Eac~eX6b=oV=ZYm9^ zvy$HN+?cOVbDgHyRXZlv`;{wymkn+6aH%BiR#1xaPr22MB&v$dUt`0np?Lk0_uZhs zfA4$Wn-TNpCq8g9eD-VSG(Y+_Y%>%IYQ*#Gl8^W{tsWDr?%d)1L&b}|73ZmOr}awb zBW$uuW7-OezMAzT4cFtg5OUu`>y_t3Cdj2~roF5b#&>9=Hrq zz}iz=k6HVWb$6K#`iid1{{EXGD+&{VC8=X+Au^Y~?2M+w=(2|ID@TyKn{@WcJ=%(* z>^2}r)A%TIhOAM1AHhdj=PbB|zps410<|Cn$mB}IKCr86?f$MTL?(STBSuea;(fgN zHV=>bPOSxalu|fuBPH5{@jTgi$2|849J}W+S%$|-*=N}GFCN*Rn^eUiXvBOib$w5? zH$T@zNUtGOnQe4sziTvGL<^8#xqUqs_fTAS@%j-@Z7)aY+vA?czA>ZbOhX?C{lWcR z^p9LcKL>=C{@wcZuGuu?Bh~5q(goe+dyog@7?0Smevg6$#~$E+_Wd(g;$AA&ul;*d z*U!r3bpaKw18jYKWIaDO4|EdOMmfVqwatLmv6Rjt09cFb14q9T;KA>gL{!;dCRV0ULOr=_ zMfRHFF`Y4|RPl)qcvx(y+|&afBcc4Y+bVO54Cj<8kddYiimysyE-yv4bL14qO=XqI zU^tduwG@?KwU|NP4({HgibQoFD3IW!t$RM{Q=OMP-&!zlB@w=6;}8SRy0%8Rw+?W8 ztx-qCq&UTPJOK9CJTj)Q=j@mEvHOf=k%g)x#9g}}6FlzqAf%%91Bo;%3px-?GkV|I zFX@5x_l#;L=<&rf*2uz~5~ocyMGIC^t=)=leD=$GlOobT%Wm>V2*{|Y-gLZp_ro5~ zc>LfKaPOQ$>~oy6dyz9S8_uUbmwS<5USGb@h?v~_`6-6K%YvBQG7`jyeTI#g_1=j> zzw>n{lc`xKB+#|`X+p%GKUQO`c4zu!0aFfsP!Ge}?;;@jwCZ;Zj7vWk zuI8R01p?{!O5sPHY-ur`aE>W|oqW|ZhhC!Bz4$YNmXdi8H&j`l(;y(jy~-glWgW^% z&x>^3v@>DxsyfJt32t6zuq@i#3T$#2$T1hzQ7MLV-49Kfb&G{+kZhrI%x+7m5GX0b zoQh4P4J>;5z;Vm7-LPhN5Bzet7ydJ!1ADgrTgBE&m~7@9_1oeNWG!90rw9IHtRH@Z z^WeGdSBXiO4q}UwJ*BmcinxwEy9XWX2K(VoHD3$UjkWpO zpHwliLqGSw=mOaJ*nqYc9e&R36Yd8jbm)uR4Fr2s2=-v%0%r;3SSY15Bwt`lmEC%? zbu)}#X=#kJN$rhgTHtIlp_zlQc!0Pi?3xu{ytwaqxR1H)4+>&#WjQ&6e;!n1p|;=M zf@bSz-h_p@{ag?yNH-0S!oVMZauyTsZt_X%R@mH0M^)oGsSa-@QeR zSxB{&GZHtsEg-k|DObiq>Mfq&+PK^FfgD7goS4Wf>cHP?n3Jky@UnXwYkF} z*}v!9x}3A|I0yE3b5HZwBAzQDD1%iqXF@U;7FaJ7?Q33CLg*9jUMWUjP)hDEx`OGTYIXafoeeRfA|B~v^sDK>0 z7U0PKrlz~_j-LV?ZIDqOv~Q1}|Lk96of4w>ke;_E+u+SFYpzyre98Fl*|u#P+_h(Q z0DRk^Ea$M!1#cD48RMUjVV|0|PRZb~yKDQW-2{r42X~uGtd*1t z;4Pzde{JRaS?+|G@{d!zGgJlYL8+Yaw&PQ=d=6OQSg+b*TFM=dZF=O(0-n-s()V*- z+FNduW`aQz?`taeNTTeun+>*yzpPzjFnTsIw6}XV5h1XaiL!`9+n&gvZ2`RzZi=pTaXo;` z2}|XvgEsvs4fwQ0uP|Krdb^d+(P7JqwphP)OoLC%|AyYMWuy?MB(f|ZU5eB8O`T4V zQuM#eNVVJts!24MzwSt!$Ov;A?d#76L2OVM2$q4z2s+3~JYS4i$j?QE0z0;Rai6v% zq4w(>gGIev2{AuuiCPlzREA3@x@QDMTkt+fu0VB5Yv5n@MH5*~+vgbGlNy6*`@UwQ z=pDZjblK(_)^8orfn^3u2C#HVw~pS|{&Gsj4h*#!dI&KA-27>EOziO|n%w0&k@6Zc97q8s9Z z!*A)PwpcIoSmX@vWuxycn#_?D^lRFnU@>0GY^&RtcpD*a$toFHFD>c|0^ZAA7on## z8`Y$jDg@|_`upE~<6N^4DX#ZpfBNsfO+J6cYxOz$pty}XeTFTYMchBhN6XPI#-157azHG=;N48*Mf6tn3d2Q2eJi6;fX(EqNxa*h7` z6<1s_;ktk2^3|FF$#Fg>=g$JSgPvG_4mNl1Z^Z(7!AukaN+#eYT-2DI5gnw!>p&uX z{XJtaw+~@pIM-3{ecej?c2apxoR%$sle3a~LFz3cS#kfmtpAxRiKzI#a`cUVzp@q^ zbWBd3?116A1UAPoWeJTF1aHRhUQlAca&{~sm{#9Cs22d#W{Y~dnJ}Hewmmi$@O0b< zcF|LO=BrQX)mx6S@YLIqXeM(|yw0Xga-&BI0ap)j@!}8L<{km}KDY~BHUBv;NS#Qb ziM!|UH^cD5Kk#j=6IL+RC@m^9Tav^eS{|rF1$l;VuJ4uc^UlJ(qVpGa6@oUG_niqL zO^;OEN04zfmA#irp8L>2N5c!Be9*Vw1M?5}>{c&Ivzg-^XWFZ##iZVj&#Wafw?VX? z-HO(gBC~Tq5RUXdhhlOAtm^}=y`A5$$pV!{uNz^wW|N~rD1RRb_aqDp_dRVgM`^xl zO>Zi*=&Kjp@Ic;Fub4eqHw!e$;AN?8yh8`}(U{LIHE#brq0Rj!~+=*T}aNv~R47 zYHip2HWLNxj1i^d3C3mwWd*^a<%5K2RT*<%d0k6o?b+~#wp&N46BxCZgQ=R$g+7fA z5=xh@8Sp-8&0ReDeDR>7TvJghDo%guKk{ub_|Ol=?R?GVNE&Z&B0);W_1{ z`sY)7cER8o<>z>m$pQj-F)|SgtcajY5BK2D=CA;oZeQlqKba zS`bAkaoU=tFIai+tt&r)yI>zbLDvU$f3uW3_~PxG)GmYkeo?k0lCkF73moHQ8>#o`s^llyV~zAU}$NvO;q0Q zCM)HtRlf)4pMPfQT0T0t{X217aPhxbQ3}=%v@A+7m8me=Mc}{l#47ZHv)U^5ddIJ{ zV<~M?*e1HO-`-;=pVfQJ!;^*VMLeLzZF~A{1M5itmw$Fk%hyEd&$yGl1XiR@&)!|+f+q%DW-JlSpTOKjs{j#&xH0}ogEylAcE8Idq@+B!0WvT|KtNtS| z@Xqq&N6IayUD*@?)tO*Q5eYb%!o9p~aW`z(TKB?*-bZLG9Yn$o^8cgYto~jsglP_Q zdIEZoteMAQ2!cYkC}^hR#d*@571nLR(RDwvyBm&SSTKxwJ;aDIgea$Z={AC3EhNh3 zFNr917sZcC&>#2?MVugExkii8R^^y>N1*5WSjfGY#}))?++MED+_va)9i*p9gM=S< z6iT`P9~PAo1V|O-L`VJ%IO`6CRot3QBO%}<&*ej?s*MXOq>a=4EFRqi){F)6xov(= zp@^a?QANZH7WBp+ABlic@}9%Y3v}YN4vs+M6c>bmT;jwEzWd{D?V_G8_{eGV+GJ{( zSQ*D*E~p_;qf9X}yVJ%0-?gRlKK7oU>+fIshc|eiQV|$ypB+@H6bRWlI-+!Z1(JY} z2KQ|RBDufar!G4~tnf|l@DbCY3o$~G&i-{4cvC_jB?mqGK%f$7Jbk2L zJaH-&2_-A6+R&c7&TSD+Q)~lBt5V6P46A(+i!Oyl#32p+K>00jE@~(kO#4XLviIz` zNjSB+F3P0Dbg5Tq>yx$touy=Wqz6YS8 zm81BLxGxp~_tf>4=r*^_SX}p_-daoT1PA zh$dc^gD-`}GemsS5b++KH`Jn%UzhtCZ2QxeJMAB9WRxBMjLT^b%NFzrCM85jE_Yo{ zZ1eUuW!o(63d$T?S~#LRS9y8>STq*D#+f8a9U>`^52E|5Ez%Go=yNuP9sGJd)=|#; zl`G$(t&xxa;zyO^@bDdPD*oMXN(E_p5gc}K-u(VE;D?ttPUzvR@Fg0A&h%y68~iu| z9VApoltT3?JN#}%XRvRCHJ!JRa5=%Frd8rWDF01WlKHVDWaL>0v6S(a2V?_6l+IIF zdxX(JF<(-MkTs^rZ*4e#!ou*KHn%#rFx4_hSYfCCN=3N^Nq~(CNPlD#i~eFJa7yP& z-#2FSB|piDT||K+61+ubQc$WrMg)w~+qv&|T$}W)F0hD;D#|34{a4`bRqG45ozb%sC%9*6O?+eQ2y$0)p9ha@s4|)Lx;#yf{PUgIAQrBh_*i$d=C>@$nb$ zzX|^4YiIj;C3m^pm6?xpaFKQOal1YARXg-NP)}T^+q3@oDt#YU-+Gm9^F_Vgl{dHb z;jX<_R0zXUk6oDcMixZ&f@JHGg_2R#w6bAe9zx6 z&Q+8BT$O%9#WvQ2Dm8@$$ouZQ58xHy!%IxpY55@HgxXUz(cCZZ8i3I;^YfCiU9hoh ze_>Uu{G6!J3PXNdEX#cHa?}g^;qIIXj8ZZMfI$+Z%ql#%^BND%=a)y;{}m_piEZ%Z zek-4qu2L$S|GYF zvhuBHkj7SSlUKiID;MhZFgdzFkXOX z6Km793DWk?1-!fd_xJq!xM%*|-@gvxtuy5puHcis0H}^2?O00F0+x$dZ1JH$@ox&R zln#0*(-5)or;7Z+XnoPD*_l$LOx;?t*@wG?&ua3+r`Ldv6}JW(-pdvJLohrd&sj3| ztcK%lh15KPL+zFk%0Wt**f#bP;7)Ko>+#;<9)!$q<7TIVu9F>*!N@(;Kv zH=6}NWCR`{7T^PQja{Ua0Rom)S$E0+r{#;~qR?8y6n|q6viL+fZVw`S!YCJzG~#sfYy z6GI1cZKm(j7K2{O?7g7RJau80WIBpqCr1xZavXG254-Kn13x@(0yz&f^ntcK^C$zX z+;y$nV*OR?)=~uqRix`|5l6~F&TW7T^#R}BI$}Hb*?ct9p+*tgb&(~=oGS(Cx-BC! zYVMT5NantgB{YBHC%Wwqf8qgn^w1X@cO*ncF+mZ?X5um0IY(i8#`(lN`uQtgE5-|o z-lzLbmSZnSU4844u930WkIX%J8J65zI>#&*r6ubspOmB3Qq1)fLJOg!IQfP?3PGA! zW_wY9BI^t?NVh*1`F?vjO4O}Tg_uAL77103Y;}NPEJVWi$w)fn`RDogGxZQJ!Bb_=Y6KIM4@YD9vju}BZEv#6hZu<6}GSBZ5Z>`SuXcM9jvl>&ZZ|h-pG9Im;ON zkLKWzP=PZ^2c<4F*d_&mGn#ozFkpmyVth+FS7U^LadRXTW+FK8sy{lgfj?-b zxrg?j^7L6V+uSBUeLztim)TaV85~ynnKNah`9~bvbSg;2Fl6AdOS&CZZgES*3pD|i zl*^uu?fV~L+EZZ~y;PK22ji=mqZ6%}z1NwI$X6{{Nz3C7U285dLJseBLQgfG3H4&2 z0lukdZ_<~UO;>5Sn;F9dhPVTcfy!`ZB~0W@PiINYpSTW=+x-xXjG24)g2(UI-yb>T z81r1@VKL}gqdH%8`z@SpJzpbY~7H){FikPz*s#D z_;;ejQs$1Y`!AX`-N@2>-F6%ar!qNp@EX#@! zu$d)OxUKoT6fk67C(DGhXo3|<#v+-Ch;7&QnLn2%kq~s}aWx|IjH`dJz=q5-ENF#W zcrcW~%SM!o6OR<~JVuFEqJy@o%fb{}y@8B3)f_#eGE*6|Y;vLQc%Ir9(=GyDiciAe zV8|a&`QIO$|3b-MMTQj<3kusNSrF?D-CCM`k|VCF6UDkCK;BYYRBxJ;7e*4q&lZ@) zXaDQJ{wuuw?QfqkmQrWwbCy8j*7CVUyw`LZzp&v8%~XQ(=f{tW?8ps^m*#o%|?sbpr*x!Ps)$Anq%4} z->U-qvbtZYYefP;=K<(125XIiJPF>J^HsFABC0uQ+lftIRE4C{W*N}-PgmV|9D=@S4Io8zyIk! z!F%5Du4!bX>4?(3J7K8iC)FnB#c6eX>iZ|dU;Xy46PK=v!Lt}dGxOc8XirkRwY4;G z1Kal?_zV-OtU($*uHV}5M%a7LAWlkQltWyCw?FS|zpBsGQNcDpkVZh!;RNXe5AA^+ z&vyIOxA0R0yIq!mmP#`xL%9*;quv+3HEb`ZN$0B{$j+0gJoMQtBt7791;p$O2E4ILv&G4 z+SkxpMwDWaxRx5g{XTiw+JdY7Rco+Y{Yo(64$O%4-+q(BRN+RDutCt6Sq zTA6qDokRD7Jo9~po~z@IDi%S{>`wOs+m9T+%lU5WcAoyM;f9uj>Gqc;_w9Dv{ ziF9?j6nkcOXmqT-%tP}3TuBk~sv@ddNnR>I)DDR@;-ZoSDAig+&8@)EKNpo*xunmu z3xWVk3$bNYsYISdpChgneAKVWjXfebl}0pR;8sEaf_wB9s(^fokWy%7Wu0EJB;sQ{ zR8)3gkLDT_A14`@jEICp`?YE%E%kL~A#%|8+}{H;v8JBu`}cc+j{Fa0pY8bScwWX3et5Bzo8&vNw(>{RdzlbJT3hI<(>T00JS5ghr< zPX9g%cB0HkU{PEoWSu{z3FOOR#mYCs6TetBWrDKR^Rc47LxkW5* z6Ne1r3)C=1=Jt7=S$(4;O53g66s8TM3igWiZYl-YEzkDAY5NUZiz(=B{PHfM8O%TV z!CT?VE3cgJXU#qJI{3t?0Dt|JGgFB9hUdQH6|3N*|LfQ(Z|na4{uYL-Gz&_pM)hzn&0?VD?$e=`iuW~O1c?#p5F z!G!J}D2}jkqTbvr8@Q+7H`#%Z^&uQT^rW%+?{_!=vxM~={w5fGbd|RnaiOnRV5Xm_ zC%GVAyyW*`(;fda+%pvtDO9x$Ha`%AH9X^;BJX36rx&L)X{MwqX6%_#0sr;TK}U%^ z@SqqImn|l1hn!cua24Es+tskRw|m?kyK2?VQ(C8UkFM?qF0sQ$-Yv0EpSk=jQ*UQ6 zXTJ4vv8qJ>4sd;d+tyqM7oC4$M}BogX^X3_8RF7$+pZpOeKOIrOh_K}HvRp%2fshX zEjv9Lb6{Yg;p-pxho|6vX7xJ#q`v0+MM;>J`AIPWinh9Wz)%R#Cug3P3#;6p3> z;aeLfwvb5&*2IFWeEp(Y*m@_REKdZ_Pd8Ue&2!9_j{qw-sj9v)9KGf9$rl3IxI~!u zt-0G=)8fAFatS8P9a0hS;SJ&QC}k(r(`9s0e*50u%i?o?anG1%YS4WkAvKXj>f$8; zn>KzYaV6-JU$na5{oEg{(kX(K_K$QyXVDGE@Hx(9<-WOxg@|)@Peva3k!fe18=ZAD z1eP=02UbmP;VuF;89Bv$|MsMUQojq0BR4~Dp4n3+MyNxCs=+Owz(OajKk*YE_&24- z&^FmzKlYxVmHtLJsLy=$EZ^yPzI)!^+y|WV(muH1&S4Rd*a^U&C8D&^c75e*BG^Js zg$U3v@_9NRN4{J_4Ch)IZ zzPhCe>irk3tbFa`->$fV;)nje8g!55ek(9WLh)SQAyQlR6Cat)hbS9?Y^?GKW5wi8 zR?$+~%paFWbhpdrX!A&&6$~N6m#>HNuX9o25o0Rc1ApC_^1;m*N9QYpw$jW}&Ey=l zQP&QKmK!{li1-JON+Zh*=IBkhKC;yc865%a@|iQ#5JEt2(fy(TEPYDGqNeFOatUES zl3PP#{_<;)rE_}Z=p|* zsGHxl83g{K#-2fhG_wKjsi^eKZDacP@(A|8cAa#aFeH>mcxhmJ8`_$p$ZcQA7*;G~ z$m0*KYr7eSgc2w=le-La>oaZJ#E(^ZXcL3}Vo0crp4qJN;(jk2uRnTEPllhl_@b&RQ z`Bq?+RzU62Z&TC>cU->=*qrF|+6y2%Yn#9N;H_=cq*kDX2GoDMbnT$93i3SfXdiO7 zlH_@Ww~V$9wc9!x0){k}gKaH2i)0K%$7rh;llERL30W>ogWoBZ1r~(AchxfK8{+$! zV$>;=7@>A?WFZ2Zqs8}FKTmXm&D94Oq#mJ!gz{`k71|@9fs9~umRPbT()RmfPY%QV zPj$iZ8Ru$>C)Z6470ga|Z=IE{mN?gxy?I0ll#>?}2_f`EAxK^89?S$P|G6q#8W&)7 zSAR5?q9c0$Q}^-Xj$aPjwykZ;cn}0>;1W-!Q)s3qDha!X%+|>;OjV}*f-{It3;k!D zQa8aGq2dIb0z+sDqLq><1mQS2?3ri}d!My1ZGePowp?n1dbCLO^~^BL5iI(iN8-;2 zQR;RXloU~DS+in{wTt&H_dX3zkL_2CcM1-jGYC(P%r*VYKDN~)32M7tm3o!t1p1s6 zOL{d8!6m(LBn0C!q+n4`w^($xqI+Gxqu@xJcNE-(dloL%>^*036mCe$LLaQr_(VSI zme?@U`bI~Tw!vzunhe01?#KQ2-`|8hv|9%FeAQ_Jd%h8K@eS`?VIJ_}HU*MOsA&mGT#$5T>eW_;<=$Z_ZzmKd1jhIq3IFpB%^K022X!r3G5W_CEs3 zGX?8$^8KdSmY{9>)Je-0_v-EHC+;0fmdP!q<5^Ebs?dbX16#Bl-g5_RYm=pPDi*uQ z7akC{@O^fkB;Yjl`ErY1tn#hkB~(~ft>*g=2?ugbnXpLb%Mk#9Kz_f*i&Z%JwqCnw z)Fuxw8J)T^BSs7{qpn>ZVoTTB&7*MKAv0}eWl2`5`hqeU-AtRz^BXfy6@t`^yEv{x z@0TvUd9T!F?9R6|dJ;sxb;)i-zm(Pq$)Ogz2CT(!e2p@jEvU1~r?mAg&~!%aeWt!F zY8k+hZJvkhO37s74R2KRrho(D=pi2Dk6;*?>o$#4f3}M9mXDLuK3R{{J2_gZnYt(5 zLsxVPJ_pY8@}%5gRyJn`u(HkfJMX-6V)x+{)paTnDs8$-sEF)V45nYYWf8WiR5azc ze=LKpuJCFp=Xoocd@8CdtuW@pj~{qK|90QpLnk;Uln-)CA XL|AOM`2t4p)y2D z0dtdSXCeeOC1ZxAV107m^2ygDe4=pE!J)x*48Z(^JD_z+A++8Ixs51Byd^W zwI)QZu_%AwBwzFTdGA>P*Iuz^#$kSZkRN~uWaU^loz=|(4@O4o+C_=lWMpIv`g*&0 zr-IGHb+bSz1b$anm$$-_wew9Eoo;rsY%&dpTQj>{b&X@ApUEwV&JF2*jZd_;lxl8l zac);l6F=yv>y)r{yTuNkIjgOkIp|~^TShF(&F;cn{Kwap+JgIOiNPZ(YT^q*c^6rwaT=rPxFpIHkzQ6afpx z1%|mVD)(R~ZyoJB;;k_B&<}iM{G8(Vft^>gYAcpWskzK(tv@f{(PH=SZhOuO{b#`0 zM33F`INZ~Bu)Y+xwTCUVAs3`Bp8v$rCt+yBY!e?h@VNfIrTairWi;)RtM+Bxfkatp z0c?GcAqUoP4Dlmt0^9V3Z=4%A(-sHC(RkXr?(t`VG(tYLasTcJ(pf4>Q#c>a2QOKG zn#@QsO_#QfZN5{rl2?#GLd9&$vZWK4t3jnT(w?_wbKpJ3pS65pk6y9M(t_X>Y)bNh zi^>*OmxQZ_T%;%&=nz|Bl?%4v76k=kW5uA|l?70~_HA{66ROmf{P@xzKiIUju*wRp z5JlOl#QO|_I~E(27Dk3x8r*Sp@DDEjBSFepquL0u7cEJz?A;B6l1v3B3_WSnzfL?d z`<<^`<=a(NT9;xWS7vffWHNG#w;Ho%PU^AE9caXUCl8cQW%p{R*&zwIhpc1UWmea9Ul2}5oJgdDU#x2{{cH3;Y~q>$m|>>@BX%+TD5 zXMJ9-7}GW|MV*Muy^sa?+bdqftgs=iG2LwPC#CClhv1Qd@}08?jZK^GeKI-pDrR`$4h`bcN|0iJ8*aKr|484TeDX>Cp850V?=?-+v6SvZ zhm2vtHcuPvA9VSVN-^48osn6F+jo$Y`_e^aF!K1}E$G>IrLZC9T(3Oq&`fj`WKwQV z)RErC3TcC&TtJS^kkoA<>~VWYZ}lipBN`j(b)~OixkU~&VrPc?&bW;1?^Egy<5Oy_(bnhGMc5IUtLE&^UxOhOawir#&iDBB8N`tH(!uHQTs-plHt2chU(cTEGsN)B$t z*RSgHOyoVviItNRxFE%e+#5)>l^l#Alka&M%KX*~N1iFQiTKVZ?&9nE+aL1ht}4VS zk4&BF1)S^acV!3ozipd)sO4|A=P{s?Hg+8>MQ`6hz8^b=BYozzSFDB0zq)!-pLh9J z*TB#IVS{JBQee$w%A|9z{rc+AS0VE#B>KK!;8F2@a(yt&*DUZDvnN&DNXUfA_WW#5u;jq4=2#QaTQM^uB=L#Bw8KzkkN{%)_k z=B_>Kh|rEGZM>>Z|AD2Un5Y1lCUtvRZ4h3X4Z_Jd7`=v5QY);qUZme~G7i8?V0S5N z4;OGUsR1Ufv#Ad~83y1a^<2=$G42M1;m`=pn!Hkaeeu|{uz2)YVQA!nL=V2HOeH0B zi1~3~I4_BGeodtX2H?cEpD}H@{K8EbV$rS12}N#Y!%G-b-Ll zQW&0l;j)HVkeWFtxB7YSZLN&o>IswpzdanGmj;HK+hSd}X;hZo9m-xZw#yew7ErQM zHafV!<4ZAYTQ8}HE#PH~yZv=`bwy0hxRq69w-V<~wdatUz?;{P?3Wa!_LpyRG%D=D1CDB9zUG}rRX2OeeOZlvkCJ|<4M$uh z#%&c5M^c}5*u$H3AQL|hdvsg$OsJ-OulKID>4?&4BUF{Da&lJXCt+Xf2az8-3DPW! ztZW`0s9-88D8`r6fMVN!<-8%Y-Nt(1iB9yfNceM3=@mnXN)0^4KV$XW|FUB4pxw#? zCQP68B z>Ywp#Y&Qs)D_}Si|6NHKx~xld&8%N3`}2n3`K8HTHpv>@F$ z($>k=d{&Px-9=HiOXyzz%?-ZJbdObxo`MNHpZnr`n#(#X_FPe$uh}@1KmeNK$-_^u zZKphS!QCfiBh(#6%s)3S+CFEQ{x~DmziuPva}_Xm_L_2wiOLxcO2uWX@;#-@d+yqD z7S*qRx7Ro_rmCN#++J6%M7g=@ENH5ZSsUo&CQJnwE!0B9oN~Fq_rXQ68x(5Vr$*`T z&c8>oI!-~uO2HD@0=)oJCJkS$R$N<-rIjW`_$b0WnT$n=U@`ZORTjLXC z(z)ezRbDyUz?4113g*pGOpM89@#RpOK~-jKISICBh#c#?Lrpz=J`yMP={6C7Xqxk>cCd57!o$2|84+&kwG%j;y^QYXqSJJPU_6`X#?+hFXmRnYx{^9{F_ zwG#sW`a+V@Gw|Fzn^|Y{iFI{o+OgSy7zoqomzuzKx}Y@T?7ZPLL`^&D2Nd<(2u_ah6>*Bm*MDar~x zok^HDrLG@Y0b0*<%cn&h=(J)fqRG1(3zm3e$u*yKPr5EbAZA<jT$%pMdLhTzTb{6aJj9e04RP`|hP;4B@yK@5jrMD6~^R;uJ8w`2AIE z|B`%VU4L;&9sI)Hp@AH?wD@o2;U8(AyWxj_C>W0GHjnBF+we}?cj=%0@M`$P7gu^K z86Pj&GA=tynjz(vb~|RemDF1RK{2bh($?t>_l)`epB?fBxao%P!D%P;3aca?I_ncz z7<15B-EO<>YArf>1~4c52(C~4MCneF`{&nXND2!C`<$_a34T#6th!2C>)pLXCb$)p zl0%qrIq+-f2Z(a|x}R|>E`c4v$1FG*-oCq6UmFRTy9&WG_o%n|Lg;7xJA~gIN+$Km zWc9q^&SC!vYX*A#*8ANxD*FPP5o!d^Ip=ra{PX^se(!%d`AQNaOaS} zR6;dncG4nIHuuQ4`TEc~=fBaE(_fU|f8+&CH_+T(tfDH#&6LJ8O*l6^8Xwp=-iiI} zKFbNs@+96|Uq}U}(eES{%E4(<^jKi(nkJ?kV)6178}Uxj*>N4QbOBQlR5*EuU8++` zl$UbXSLQu8zpdReEb@ap(nVYzzwg+lfv04>rssUiNc)57qTtB*xt#g-EtJnR>wfxv z+qPM~`Woo&uIa_ct#_HRbX{>j=-z98e%5XrYbFEJBzYvzNaW`WEE;!yM?L~I%2^-2 z{J4PO>KG@Fjg>6Gvv}{5M=XFR4nH0qJM36^#hlXUVneT7zpCY z8>8t{F|Ok;hWZTpqY$Tic3kDJaL@LuU{CL9Fb_dQ`chQwoENh=8dejk4Hy&d0O(^ zl*6!FCK4Blzh49WN4&+iLw_M&X$xBnz>1A*K1vitHZjEpGdG|qnI?*jrzj@okDN9S zuD$hP>(>CVrT0K)Q3DZO?*~g|*|5lf&xx{~>x4&MIV-G%zaj=JEic<4sPr}X$lc6m z@gn5Rw>C`Sjsm79A0A2Du3Zq{CfY(T`4LltVZ*k&K{zXXh=9&~w=>brd8y7MHt3w( z;!2lUcCd?FcJ*GrY1A+-A>w_uNs#{4mrk>Ywo#~2K6PyE{ATa5i}H4Xd@j=w;0zU} zd|_v!RFzRk6pyv>TL&?G3=`^tZo#$35_|Z=Wy? z2a$L?nJw{=RY*mdktTQy3=C)&0br|HDtr0j?xOrrFT!Z$Oi}BoQtq;eZ(T6}l5fyb3(a;5=G*TY7Pu!8rtbAsKQRKAc3Je#4)|TX zNZdW1SNzuB44HE5-{}3XK4p%+?mdMtb)PV>^D5(eDJ&@{5;cewzaID)SRdr-U3q|a zV%2XU-Z!j!RNVT7!%xH3LYVrpxpm5e($U|GSg3gry1p+7tA!V#cG<=(9GRW8eX;}O z6MNM|HFb+mhj_^lo3{40B3`(dbADlF0^@AntnH6EPGZ9=RVQ=ZuCD}?jdIX&*WWC6 z)M20Ky$b8XLh3lAG{)rC=g==+7}NIr_ni*M79wTIiN8PLx_tV}uhONi+cIpPJ8VCC z$6$c0D6`KLEkII95oW3~bwW&c1+=M}86TGXH!1BZJp*H7IrQ{&`MxqZth@o@@KJ=r z`)bT+>7sMd1PC;%k|%k5aM>JD;)j;^Yqz4!BXuDxo!f#*uM2*0;?t1&6v`$z$}wC` z88zbvtIw&4v8S_*Kg&dEqZ^JbJcx}B5~i(`Gj|-2^T38T?6vlBg4A7IExSX2lAAp) z{->v*){{+kBeAirj*exEdpriJ&Vrd}`+ZIiMF5Z3mAM%le6IOe3o(JjU(!KPeQ37n z?Mj;bGWFIs(~Wa`Griq^_9?xwAu}>vr)!$F#AD+E66Y_Uy9b7bp&XROGDu;?f~;XO zDl7}3lG&RVP-!hHZ~4;k{%<@5zx7}CiZm6!lPgF&t)%0R7dR!)@7@A&r?%SZ86!A& zScLX^-)7e&w0+xclT{%1fMtxyiDs6I@83G-LeONBPxSsH+smDdJIKCfB~6YYVhi0g z2oWLbb;@zyrHus0cOY#CIQ&2(NGSzus_9m(`aS*q{PWM6@=8_Rx~ng}Nq@iWf4ouN z_u}~PfBNt2HM?w&7}#Pi^A?hh2<=!(D@1C%bq!5$&-RspWBkjue8A{^pPhgp6@fhN zUl#O1e8P2G#(ay@=Mo~O%#>q6KTQU-lGT;6Dd~mvn79H_uHu1EB}A2phNu5_57wca zt=ycelFTP#3GDAHgz2w_v>0{{`+EDQmiet}j~)@t)*y^7j!ILF`}Ep9{qS2oyGs^8 zl?voz!9Egw#-0ilteg;CO2oBFW2~TzV)G)P_<7aWjX!40$8D!|%VjzG=hYrVi${4Put(oY397yDVXEA!FQW`|#3&Iuzbw1U!m+gWLzrLmqO;JfVh zJ)L~}-Gh@@sRm#Yx=SG{7nD;#c#geWNAWW z+Jyy;mVRbvI5!uiaFw%t8-I5Dlsc?W<=9mgGGAQ1$7g^L(WwlL;(V!mDY<==-4^DW zGrb>{>!?c?cKdT(4q#WdVv&T}JCc{pB3eUc3rx&cT!mnA%l@;INQ>9olleiKEKo}2 zQXsO(Zu)^DFg3dnL_ofMy=uY_RzdzSlZybQG6WXA8Q(_4v}mB{`N7d38Rit?bk9H} zT-kMVrl{Y_w120va#bcA=q)a5Axe;Nz2$%pV!lyq#5NasTqN*qaFgpfY>$d=%-MeK z+HLf`QWDwad`rEb6);SYM`5Y7UN*=8-_KIGoS3e#WwZ{9r{MACX*ZR4)>U#snEZlQ z-Xo6pa$`h31(EXY#1XyWJu6`8f-c`jOjI*N=Gc0WAVp*xQjKDA!UTMTJ)wHMuU+xg zUCVUta)_Vf2~;7TyhXo?qO99tC4J4iUa2jB8h@lhG`Qzt&X#FYa7u0DyE0fm%yJ>Z z+!&?lADP8zS`pnkRT)K8(}ofi z*F`xC$8dm%+q%09Mw4EnslW0p!2}*L+(Fo zl4?l;*K^n2%XPN7$q3Td{mH4}S+x-MoL~P87Nxx}UllcT9w7G&CePvalxmZM;@$n= zjMMf^I8&?>@?4?RRE&IAEE+~d&O79Mqs07ss(%ruLGd9Oa{+< z3QA~STJpxF{NIEqs*Il_5uCw5Be_a(tAwr_9P(mj$ao@yAn7o&b+D-P6Ms?<8 zWBME(6o3+&lqOBg;(<@k#BqV*1i>;R? zRsg@(XpvGJgC?KK+SO}Dv{ zwcnQepAm!({c{FhkhQG3E&MMOU+($% zo3EWCpF?f0wU7Mo)3^DmZ zh$;>Ky^>uCzMquKMo~7KvfbzKvg66Xbqy7+^RV9EO^T7XysW*#@7lZmx7n7mY5k1l z8FfUqyA9++m|MR)muX5{pY1_`YUjUnYO|dYC()%Gbmm8Mjh)g zb0Q7Ygxg#!p5i_>$@`hPNt2cRU?E5!-809q88hQDykb$eM_g&KVG|-Cs4CR4Vv0XNOtFcsoJ|9(japTLD*-e6I4IlE6RHQHaxG9Cvv*S3b zORczG&J|=TdYi(~YKX}`viFQVoD7RolwS!eo{8vl+n7ELTL9=c>IZ09xEvuy7ShKC z`;7oq=GtjNYx0f<0j{w>JRwB9kfyIX3MABW3)ttFpvee~kPtzM1P`hW&%x*3F(3Z! z*4@!UHe8QkBiG^M599`^H$%0BYvV@;`r(9-A4C7`;X{stLms&|*{@7nxkbYBI0m%X zy{@^;A)(Iq;@dHM{rj`%>E;%68x*a-a<<#0S~I52rl|Z`p3$i-lDAsiwP*}sT=b?2 zAnRw&f+@^yRVJ`IdDQWjEvgozUs^K|9=a$Xga%!cmBOxYwIg@HTZF6?Hg~dX#>Y~%=1)4E2K7dl{Kog420#AV?XaLbYwLjP z%A#PP%Uxdj#5JiV%V~5_0L|rJT?6M{xC~BXNfw&vTN^fPm~b86@rrb*zxc&3CRE=3 z^S6Re=5CJ%c0Q-YM~%%Ag~*Tsm;KX%QU zH4|>{cfK-pA7yU5nZDyne$1DA`&m#8?#tStgJF5!lm7Qd7hMSO#823s*El|0f zq~`fVX)$Ha@4ia<1~l+1?ZERpqO?5Ws0N5qtQMUdqZ1ERWv!u-B&)$2$S#nhO{^#_aut`FhBoIhwwY%8h=f7cRgM<>G z2qL`y-`Ia+8)Kps5JFgd3=-klBt?us1P9s1CP|=G0%=j+ATYrQZBhau6nB+2OuAjK zPgR|&Q`OZsP28E=u$q~ByQ{matE+x>>YVQZjdmF}sV;4)2Kl6XP!QOqOA^FxiClrl zIE{VqAODF&^>-y20uP)C@{503{^5M65w8$i>p(wu`*!R4AR>n*Kq8Oz{rLxh5lh|L z1?zT!s+)Ggvwd3fVr&P9xG2-_#a^%7dPKSuvs0Q9+DImzH~3x3VRpr zqz-v8dC4EYMm!HPWFTbwolw-@cS{x3`v>3GKSzG?#;Fmc4R+_1)R^2MX&X7@9uKC# zkq1zaAbfzWYN0L9PG;$DFG^dTWuzdrDj7lP1qL!ST~!OXSfHM@Vt&gn#YeUb!XcDL zVM-(v{h$z z=CDPDz&l1P4J_*OxTV~R*Gd|9#xxH|Eo%+y(4w1Z4PXHZwT_zF1* z3B{;?2&-28XhLu4goB#5k2BwSO~dcc|LO?_f2VS{dYR>viZ$17dw|eV<2zDxMd?i2 z8Zbc>MhY!u_iJ@6u#F3dGaFUtU^w>JKY<&5_#gVyfBW~l;kQ2=Fkd`%n)ZQerAJmu zT6d)!SEd6ICwG=sXnC?1Y@fX3NPng&;RyR2zOCu-4aET7w z$+3gw%QWdjrt<7qfF-qke3od@OJVcm$!Z=(HG}j{*3;)acD#*G@$yfQIL_f z_OlSAKteXKaNrHQb{*Q2IfF#|mSL!9cew$?3r?|T8T*M>kT|0_WX+br;9c13ARHeH z=a>ZP&X!I`nVhsWlzF2B#kWD5wX7CoJPTF;gb2+8m$S7{q6*52iFn0!&t}th&4E{s9lz5YZW^cFJdWAId=A(+TOJTYfUM3Emf`4 zz)D)(W-$s5!!cA!r`N^7FPOZx@!077xRaJWY;m;0uykQhIrwlK?>GpIL>!mr10>w!vs7V6D(e^P}PtC?6o9|A&?1`pVmt)k3t)xVK$CPu=`1shibmj(Q1T6qkWf`>Ai>h?tbK*$3eq0@9_-MoA+KAu zpY}0KvQ4qWP7c@;Kt`H#Bxx9}Kd`VbWKD{buH7)~?w>jbaQ=GiUjy!C&N44hf~+2s zDnvuKfw+_5^ondjllUdS%CEe$Kca~G4Utb{ms1$jw^AI{ynA(IT)(nTCqgV&mdUs* z2+u9a7XSU<|J~6!|NM{qxyheYr@N)Uvs|ayBw-2?4+ag8P;FRAgT6uvgt1r|!T8-` z-3WNSG7>#6x+mI4G{TSntdSWXI*oNM3%7&N7hJ?0(}1bnu8gTR&U8iT?zo9r zpGpFMVhfP!=p3j*kxbjG`gg(b2tvIOZ$Di71iZ2a@IU$7z(PX*ds$B>s?^#&gxed> z_KYA!$IV=}uwO*?V~L^4+o8QNDyn!hYZYA`dSBO{Pr+ji{eIgwbAH}V5FBqdW=D>L zov}1A3fkM$bzn&-eUtsUvksW5fRlS0SZ30Wr#R+!WBH zS0}O^VN-lyhhi8#>$Q+K@aaomYwoMibreuU|8y>S%i+~r(5!Bjm_flmuVgh0N6l|I=Q`+V8sBggr0)xxKgss)xp~{i z%5!1xxYy}q3jT2|Kg^IR5dFlOeUs%a4ipm^6TM$|zLr`z*1T{eQR#eX6ED2ldYwM^ zfiL<)c=+L8xQcw>fd}BgdG;FjIRWs=>-_aclT<{k^hr)mdaL%1mhZVvzI^@H;iG@{ zw>rjwwgn3oG;J!g!S{5=i_%V)h{KQsHG$XXf6BH-R)LyE*c3CrdKm4bXKB!0-t^Ml zsj?u|Gk;s8j3q*{Y8BfT(sxr4fjX9EBLjNaUQ{R>(6~*Aa=>77v2mc@2`o8# z9Y2xd2i3Ujslti0yL9h6YvuHW@f`8lohJ36MOjo-3v4ZH>l8lfR%4Wkfp`rCTQGG% zsR?N#*eYTM+i7>={bx*+76!@-*O=L82k?P~y-q}N0uQo?IpGrM*qHTc{zt1cIFuC_GtC)PWG6|~K#nrVGY&q(bqZCW9o&>33LK!aY!amRJ)XxNp z_hKl(@lg=m^2I#{oy6tlCN@E%l`_x7X7m!bodX`bAD(#r%ZmNX_xTgoxOZJo5gAnm zK04mjnH9P@GC{)fR0VIh^sFHiqa2A(pX~F{X84P@z7jrj%hUS0^T)5#7N%U~rGzwj z-VJh^m6p;*gQW_rTuR6dltfA~kSI9!1Gm8&Z+_#9t(R*qT?3!I_{aoH%~%LTvM4uj zE$pjxIE+t|ty5#OFjkK@e~zsOJRrxNVYBO=E;DUMv=z`=Z^Rj=x@vZ>3WB<9Wj@+& z+u?!Eh#z#KfPy;KZXEG~#$LO z?yZ|vqmRq2ZzeFd#*|H2+xYkmyM|pd1Lq5vtKgYoAUeHZa1#qVh=Z0JmP4B7L3>@N zqoBbH0ik#`$CRzB3(c{90Jq1W5Wu1>(f)khYc>u#W~M7Ur@AvjMb|g`tJ?ZLf9+1U zsLHT+Du2VE^>H*#q}InV_a;IsWcb3BOc>Bk-_oiWX8xx_CuTTSPS+KLY*^Iw&!R2s zygS6|>(O(Q+=wmn4p}h1_4&+gyI?`8pJT3^J4-00&9jW3HMavIed@p>k)D(Geeu%| z!pNvOe!qwB(LYI?njl**TKV~Luw@_+_2kI}sVVEvs)VS|?XkL@StOL%$F}+0_|Cp? z>pd_yY}(qteCHSN+~Vh>`@h6Y%yJ0e`TXzpHP^x4ob;})3Z1E2=ZNn^~$xU)dxhz`7<;dg4SEM>`@M!$s@7S=b z^p#6zszs;BKv&D6b`ai&7V0${9*C&2V$x$a68c#Uy@eM&qUh7N7>gwb^|0XG zG(74Aai%8;J;t{mp>u1RJxrEO;>k=vY|xHnoYw7qWj1)s1hARwuG zgZ9#hBEY&w)QSHw8qYkND4HJ4vNS3mpu+bcDGtjQaSB${S*|pb(_XA00~iaiYkz`3 zvCJ|%wM1f3TEi%)CwKj_zcyv@TYL|mX-XI_YDavmjwDAD5XYjF+Zc<|nhluC>{7J8 zW_#UEO!w5>xJZFWn#KTOo#}R*LqI10OG0p;*?^yAcG3WedWk6+^8LcB8vjOw0uuy= zNy>vq)Oq|Px5eOD1BUO8=s*0mnOCQB?qKiZ*jM($jlVGTiaMjky5s5W5v8qKO`EQ) zNWP(c5#RX6-Dl~(Q|lIY&VG>cpW}EFz^7hCc6JEYZ5GvY8y5Sj=Yvs)2GLv|aeCDM z&Ye43x<~y_*|2KCd6e75?|P_%XNB$U7BM$@5FD>|#0Vm-MYIOO(s@%jD!vXz%kWa8 z6iI|uVrwf}WD|JzDI1`?`DJz~bjadmpIx zsgpI4mU1)Gjy%do$E*k>m*GQh9hwi>Z=QjJU$loVJF_oOX6r@ceYEeTy>IbsT-mms zO%R(3P(RLsNA=BJ0vi4*ql5UqcnLbVZkvA7h)RRH((W2)th6MO=zH#00v;&%Bx#uy z#B_X(%SKzaby?8uK%cu7ycaGQ%w98>&3GfKZxHwF++Z?xTV*D##UIh}nOXkMte=6r zZ|=zk4x3}ewmEOjiq^o@Cs*#cn!RpQXSL*ONc-fbmDp!(+8w<+)HbBmm3%(=S=MZT z5xXPkXQy3fvfx?AbryUVZI3_qVCc!%4aD9%yQNsvRd<_ZmeMN0O8+kU-WQ`$E0re4 z52WoZ-_NATxl)XOf>GM4!kbA;_tiGP@x&Z8Xr4{3`GR*on7k?qdbs$KJKCz7(@tGc zLJeWNRcKcl5F%FTWXv&a{b8K_D7c2PE!|_3=m0olomcN)r$Pe)5NDbD%Kp-2#6Ev2G?B{Csp!t&3%X61efqsKw_uXD=Rwa+Fk zk@NQSiw^VehCSD^<)^^<^{dQr`<-A!?PFK_HXd0(%>*H|vO41c`iZ7D+~}zlJbTa* z*yGoC2ZB`A6V=IUk9rgQ;KuL5u}7bx+y9SlzN)K0XR|16%jXmW)6{GYGM`#S+1(m$ zpTB*F_U~e=2F>u<37@TQdg+v#uwANaSCG5|#XSXC=nbz*T| zh3(#7gtRKPN~}IF_~>seea{h>;@X-&cu2n)SaI&w-m{WNaPzckC##4QBsw$15IqsPkFLv%0kmsdcR^R+R z{p;$Rz6VDi=~rC$+G{U(=9y<)zcbsjJM9*tbmG%dCLGr>c6#2;Qag@Q!xk$kQAgNS z>xp3mKK22doBAi0cKm$iz3N&x_f?=N2#8SPA%SPs49N2uf8y);;gqrp4C zo|x22@Z&9Yx9m!X5@*vb1L}Z@%wbS+n^A_XUzuGZG}egR2bkD&gj!5zCUxSYn+97H zoh@476T2D6ybbiwIkK&gx4wSL=FFr_I8JPX$sWY%a(QV|Mr6An5U!J+EGSzEztF7a z%cjCj;Eb|mgAv48&5<08FQ4&&)M+|3b;r~{p{9s|>Z9Tl%t&T_)G@%2f6D!l)V==QwI_1;L}HE zHch4{DH!w?f3{-z8+F^h_15pYI`fz(E}NcZW{!0ztK3+3gsyIHS!D_XoR%g-I1+$OM($X(_WADfdQeZ_;54X8JwIjW2}-HpHq+KE{)W?-Iv+0^xh&Bz z;Ihl8u$}WVH!|B2ed}iS`hEQx!Dx9{7!O20!l@dHp@aLAo3rOq@!HOkw z0R^;N3)2mQAYVpzu3QRJEOQkFPnFt$<9z}I-=&z0AnJkfI_xr_B+7}~DLsRlWl<_A zYRhGF`J4LogM&vO4+N>Klb!=k))OD%QT7~glHOhxlBU_sM1F7D69B53`@NuDWYMFYJQ0VMV7rm&b#dCI6hSI}c&-Jh5GK z+m)^@&>@qM!te)tAk}5(9zi1u(B{xcze$n#%e5 z=Jp+Cq!k3$Vc4*_ts}PP;}h2c+TgFC&cwTI{`r2)`4c2TB$z@bwpEB0}&PmfSZ=fy@mj z?<=@AC*sfxe&x$hXoRV@mOj3Yt419-7o~NUfAQF!+rDiw|v!_ZwvP4$fH+TcZv*# zAHB*O4TR+wh1HCN=^Y#DK0B4&*K=dVs*v&%3?(g>#m8i6)j?FnxetH&JU2lBVOiG1 z0c|xObz=del{AYJ!^sZuRr9*%YNF2KH)>Zg`h6QzzC$%UTw%c#FIPItkP-@^jk6{#|7O$+=3Cy?`Z04fsK>D z`}a&#He&gG!O(#4q9=b1LlJxP;eB5e2FsNfYy!*{LG&wurJ-`>y%>;3KfZh+5!<@n(34enP2`jsLD zJ4h!w8^r4@7Nr=C=a>{47;s8w0GU8$zmHf)=K~fF9_3tDGfR}W+^+=;JZA5y@x6zr zY{dh*br(Pz`Dt@a2BV7a7^O%;Cp6;@kq5BA66-ovYh4TmKy=(x7D%*{6VrZ98?sAJwfT#NcKay6*fw*{9S7e`P`0Lde^5OCireQd+zVbdnLoKB^kf=fft8 z=F&rZ!O))U^DG4AkMGGvG_$pufoGH&RFiMJBtXeUBVa&U%fDiVW6Yl9NN#d<3$6@#qI zXD*xD6f1W5PbR02I&+y}{64m&c=pQ+wb zC@^uRPtn*jWvuh$${_pSZh%u)ls5GzbeNDfH0exeRAHWV6p~%e*m*Xt#=Sq-U78Io zZPOomc@gDO+W2k6)pKIe`9bB?;*FR0nKxL=-1W-Tl%Yin{ZbPT9s+@`?+dYPr4<+( zK$VP8)|NN)-;*FkA?Qs?P4tK$h7dVQiN_vE)el7ym()3=@?l# zIM`8nAtl9^1fjD}Dn`KX&r*h1=?$;APh-ANiGUUHp6`cDY-o7WCbNMs6O}+8-qu~1&-=shP z;9p-G9Q(P;j)NZZDYar-PsUU@5pXPC=GJD$k2ULx(3vkv$0`breuY^|cx>A+Jh0U_ z7;=&LUHYwWPyYS=?uO+pO-fSRM}lSl z&brD@2D0R8aSNA>$zw2DC#a_M$}h!=Q{|Bo)yTqvH;%3j4H3bk2!A6Hbf(u$Y z2uqI*<5j07)+yib4neJ_$BAl%fjL}Zm;yXQ^MF9rnjYjo`B7>M0uFe&-@-+*S zaQM1-XupGD-{0L++W-7Jc4`5Z@_>==zMQU<-wB-Lnjia_dV6bd(LbFGXS`!o@cC!H z^g6pLgK6fno1_Xhv7FR(HR$RhxOi~=W5WiX8@w>?2vD4jq8KLcizDh0)r?ul_jai9{& zU@;pMREX52FY5^}$k7mdW0!3^jZ+)Dd>KnW8y}m-!=}>-yEw8aC^4isgoKDP&s5-_ zRM;;-!>--aCoo2kx${Z-LX?4?BYdy{P!K1rqi<<27pU;N!K zi&K-fWB>K^ppM3^6+e4)u50uA#7?N9fkk$mD&8@Sial)Psj!)=^tl4=q1|oa(36$# zkcz_R*IIZwe@=djAh2pYIFWF5ZAe6lIGrxI+&Ks3i?f{3gZk>j!-kWt9~ zpA-iIpCii;g33LLMg>vbN(|_XCK{IXC>Nnj^`(Qx1cOpRIT9QKK>>nq2|@jN>`#cm zl2O@U(L7E_sIY}GDoEa!ikO@-l3PWQ**^L@7p&8;K9q{VVGy9FOq8>U*p?`x+#;4B zIv3xE#`jo!(sZ;y6w4AgAj69D%+-tbLnpNjK_zvpG9AWq>k!s_Sno%2`g z-!J&uiQ1=>mh3-$>1*|8XTRqMaOOL&vCk-XE>=qLO?lGo>N@w|P1QKowUkaXYpI+Y z$_aOXJW@iKikZ+)AD-Ebh>SV)JUMZ*>mh}e|lDws<+9u+V*Lp`Vj(#Rk8 z3U~^JM-@;k>Eik``m+tSJwkDpM`c^#@Je_RhDXe?i$;y>!iH?m5IG~{t6n;0|Ip&! z(nY<2&g2W$`(@~S4<#apnXK1*am|!XNUF*??mYt*(PRe{VWo12r2w1c<@CZ{ZyCL( zZuX^mSh}!RKd%q2nC~7d@kb@k^RT{}doK6p;(6I;cJ|5zu53aKc~NEprWW>Q{#X_A zRX=q2p6=NHmj#~?iyyLOU$Ayp$bT&UPa=r>%M0!IAjJKmIeq@R>j1f^uf=mb{o&r+ z1JsRJ0$4KFGj#8*dpsB)|KTI{)W^_u#gi)6hI8f2F3ncRrpihhZ|q-r!Ma^e_(6ni zGR#j1xT7z5_F?#stA3}CJ>aqX;n4$L;zW52o=4^D+hflx#)w4aw(DFQI`k!bYpXwP zqmNx%wKPwZ`<+-jl05VfuG1|41j%_>l1Gi4=>l=>-t#LorTKY>hZ{|J3 z4wvrH4j8mtN_HezM0gy~_j3CHMYfB(kH0s^ss{JuCwohh$C~dJ758JV3*B|m zx#RV$)cO{slieMxr17Pz#Fz5eLw5cS>QP|Qb02%4rS~dev=&?aiEE;7TS&vH68%EO z$yDO`Tz=(UQ@d>6gK+DKt!j7}8@!TOsM)oVAgvcO zxL@S+0TO)6$?O`Y%2L+aT_u*D)C8R>3O178V=zpqkWmOGNE#N3~ z5kaD(V-cfV(#5g)Gq5pxPQdFlg4FZ)h#DZ@Fura^9|1@BCxS5IW_H@CD;l@0=-zhh z8io0Dds=RVtzc#^`NA4eSK#hd#bgS>faC-Pi~G&BaFjJ|6xBXr}1h2Zw~>h;)fPW3t3p`>BbvlEx2T(hnFD=ANyfMbvXuSq?|* z%b2GU|5faVB4|fJ=I~;C{Sqf7X%xQsTRMhq|ICneGz1a!qcEE$BL_5WS65ziQ|a?h zUwW**PU4i(cK+8+Fm<8O)q#8FnW%F|qfh`{tLW?&rK-YzC5Tc?yc((nu`!cO?mr%y zXYVNthM?M5aNt{E$3x$R`3Js5`^jwo&9`UW3*)2E(IJ3jr~L5?kASmQlAu4i<2G{I zsmo#WaNVSqFaLhT5J`LwQXY;*0tk^-icq3fK8lF+QIMo&hTWe_*soX7|y z#u8+bD@)jydgtyO3-ywHt#pwdRny>DyNlrZy%CkgKa!5+Q|Y=srMnd^U>$Q+b77%IhNyfOBZdDBJk;XocUMR6k_y7_c{5R)@%SII6R>3 zBQjYp97H(^IY2UEzsoC~;mh}pOyk&KW;E-~rP2L!Eo}eocZ@aa!SBKj`h7-GEwIIJ zDp)u;aZM)1smONPY?%GY=yL*bNun}*wg_`y_-42N+!ww{|D$hzn(q~KkaR4H>^<{} zc24P)i84Zep8Y*k`nlp5@(rIi#QWW@qT?>jm+8{gNDo(f&9o_fXU5O9dVb9D9b z#mL`tz)8l6NA95epBN-72v#)szg&lzFFH)J5psqzwpIg_SgDwr@lN?0faO2!HIg7@ zUatY@o9(lgyL4aZ8T!dSG|0V7Pd5?hSM|HL9p)17iS2{31ZNIAR4XR&3J-3l6;DzQf2Ljymqi^cJ z$%k~;@2<3%teRUcT$}JA9U0A`&j#yhRJ>W#9pO6muE*^34*1HUeZ?T z1!r)*B!`WON<%ALSY_X(T4fMbt3Wn8t*Oj-7ym6lRB$f9H? zruQXF4c;ixjYOIGxvuDl&biO{-5q(z(6qn5>u!6r?PE?j{CR0fVI7Wn z676t0`iii*A@et!Ooa-YeA|g2+CR;MZy7@BOYtsN*h}$$J@Hr_ET{Tde0)o;Ehml_>wuM z&uD2CVJzaW^LuG_Wr23XF)DPXPi; z1yS!>Yl6o-SqhUDtm`+9==aNXU4|RW*e3E>AFPkUoc>}m_KO-^AFThukmYE3adG0i~+3^uBKOgsnjBaJr>a-xm=N~y2)4ANXY zzvB0OPAIPD`*7n;--Egp>Nou8O8Bc|yf^KF1q)!ujvZY~>1?oyHtj%F+I~ucOF`GP z?t8n&PNcWo+dm~{(so4Ot@qDueT=Zh-u8eGcG)~q_hQjz>fs#5%oRN6zGq-~IN%u4qDFE!4l{{Crjz!OZxpaG_tr)7b`rbETw+nKWt=MF~InXy>H(B0!S}!q>`&O zhK1?Il|%!!j%3I7>UaCj(Y8kgtWvaXF8eFh-aV(pgS7lh%XXY0sp`^hzy0<}Xs`Ba(hiq-Oa~T`I2-kS5@j{3=Pn}}t#IU)r#n1chn2-Usa&mg#g*`mS4`})$nSbfgL#mGH=S{$3p!OciyRAXM3W`1W`o0$R%{ZgTdyl6 z6NtyH?c28ppUu{wr`=wZcKtCX5rtH78WL(~qmP~SS-hOu`CE%O^H(l1kxcfsWi$^g z-%4?o)j4^!X}N732~&qbybCzi8Ow?v=IEGjla zmY-M7*;Y6mCw*Vbf`N_i9bM|s{!)%}jeXiYTpU+(*UuhTE0@gCKPeFE;0OOTz}PUJ zYP$P;$gr$e;5LXo(GK4EINU$~0PSD9=I+5slhny@E^Pe(`R9Up#gH&upL$~!YXL44=5@$m!d>Dr3Vi$d@hy2T26=_0~)pTLCw8K}E5vrV3jzQ!+?gF}RJ~ za7bWLs@?U)1e6v8`gPI=k9G?JI&Df}`QdVMWs%Rr_N#=0;}sC^HiWQYmofZMUsLPp zf#r+m=tK;<&nd+8Ij@-b>i_Jm&**b=fF`F1zI*483n(jLxuJUVKS=R@5_2KRlQuq%c`rc4-OOBCdF{ zuh6){tfxtz6;NRLrKl`VRDol&vcRIHenL9s=((+f!v=Lk<~-MtNp!;V^t=7u7 zrT}wlIF+r*6HExkFrG=a77y+o7pqtxEM+^EqC}WbtZ-DZn6yxF_uNoiH+RBHST6!} z3zQ-PNswZ6{2H>VI13eqn3&>!JBPeEH3joOY~(4}*yH`Z8j6ppd^a!zk2mTQ=Fdev zU{(pz*6#)zwvUcVZWf1xV-WR{UDRpc(}F0C_dIi8E}Xw+r<*K&{DWx$IsaAH!nxxuLN`zi<0N#B|OA-Qe+9VBL{G zoI9h+b=O4P*pX3{Y}1b6%J-&^YfYzgMQL}N7K2}V1LfGS^q4nAH?HDeE7pS4)K}D$ zPYiH;4`FM{=kM5|XYkx<>e;;r2-1U7EpwJ@#Q{SCRGkU81hWL6yJyA&6T2nw@ocr= z@6Dj9?0{YFIQ5{@;6AqxhK(upxHk9gtvmRZEP&(iJa8;!+k=0Z?F%o1$AhmQSnyme zLkyQSMUcgDZ+1AA%E7VKPup$-O$BYs)!%U9Ft+hMVgb7hDgej7cR&kA5;!YgKF`}R$@f^&N}NN3t?P~VJpr%ksTiN+vVBx$Gch_F{YrOhQ92&83sq6h zW7~wU%q*J3EUBCP(0Aediq1U>HyA?{@NU`WQXk;Np2-Jmw0~~pB6FgH8XX&*t12Lg z0-sca>q)hf9}n*VzmHEhxa(=~vNfw0s~Q2rSJKtfZFu!(tYf`Vl_N@ z$FchNFJJa!c<;Mk)$!7Ot1nw4asjr}#@i^M)h-!3II(Kw+Etq!cBxP$1Vb3;$3F%R z>vKU=@g#}_78YW)hnABwLz$P>N=a(qW2roErOm7*)%bD}#e$BN8wVJcBXwmEVH5}k z9;(5VgV9Rsulc^OCo_@a#r|uoA8V~AH(8qOxik(g&x7}u?u+{d1!<%pkGpj5AV~s> z`}{XFhT1%A1%bUR^Lbnw0a zzj-X(pE=qIIBe9k>FcK9md%EnY$#q;71DN=snKZrJ+-4G6jUT`Hb1(%-{n}Bi9OA= z%t0KRQdL!|PPFNu>s6_CEjnLDL#g8!g?-=yJ`SWcH*A zxu2#j=Z>k#0!5!DkM<4Pgy4EY9*`;AzRKf*{O5k=lZ#`OD3=jz^0-_a@2@=(yrR)bM3hot zJL_uF8E7dTi%9ix8!1Uz2(Cv|F*C$j!zXpK6busgREVX{A=Kk4DW~KaNT?^4XEtNR z8F8S~=Ha@Hpyvp9A6>7@$$SKTI4~LCF+R2&eGewkpjq^NPX;ziwTr%2!iUQESmgpa z#qqQuf+rSo{QkZ659_9?^2V0ZCvH7zTvg{-rwSn-60ATUHa=_GI%dwWW0!HYcw{@k z^Y*DFt(@(x^t1u(Oe(X;ZidYcE$^^kUauCWd(7*d5KFfn>}$>7`PJ1Ug~T`hej)tH zM>bcMp)Bvy^LYgtEe6y_lfX?6Y}1x84ubXKF!#cigo^e(1Sh!UHRLMyYzire!2~VR zKSC1bqI_+kjRjL~5Nvtf{B5k6qYfoUp!R2Xju!jXwGDI6`8`mp)%BA5W6yml9PsG< z?z$e@`#`AK03?0x;vCDDp8~ht`dwJQ;uQVfuU~t$mbOHgaGX+Cr-dNhFl7295F*Yd z@t}KNzOdhMQ6*Pa!|7FK0+Rq;xdRKmaMiw;)|ZybO8Icg`c;<03Knqho}mz!AcQ4Y zA9{9!a)~lj9zCzTl(2yId+NZ$JTgjKx6O0R_j(;1T`=6q$W&wXy-~U{HS6wrQT=kpE?|x?ckE*hN0noyA zVT0@H?AV_*x#yoXxo5eZc}Y3x#k8pV%?_dCdBT~aD~Yt3pnc<$p5R9nnt zpXBOX1+TiuR~5Qqh({7H@2lv_RjS`b;YzaYdI|#2zpuXe`=V@9#_XyQke%R)c6$8r$7fWX^!A2U53=-RsI0X#uA!(-#*$id8Y|eQk;{n=DAiWR za^D!>$uJ2eXQz3E-g1kmN@bX@1vVil2RZyc@UL@BJ%tdi7w}nq#J@WmD)(a1@iYi- z-<6khU8CWdvcDZ$f$4L?)ldihQ6cU-&+0V(&CLZasIljj9qXiWDy=G$nRatRj>YgZ zjHv;FUJ)k^d1U8YSR8RHJt9rMBbL|@v>9;0KAvCcUN-#+1rOGGGMBZ@`E4o=elo?Z z+cZ+buc5nc*E{&Y9`O6pu?C*s=hCq1a~C3aaMbKiW96J)4%R|gbI13!=+vcdy%sp? zoyw%3rkcY^c}OWAtAnA?e+KBU$plUrUs|qDvc&3pmVrx>4;tXV{PyGv4>jEx`fKwM zMtp7+p!Nddj(lEnA3h&~2e8$wn$O!p~^$P1Jz)x|32gpOjHPrgZ*WR(OeH(o0o#(R?B0sIO~a#h3EeDn^MK(X^mduX0q_Bw<;^7=pygm&Hvg^At6|yMncwSn z7LNkDE#YR$2~&r50fRXqj-g)MLyTl+f>VkT?2Xp2gd$M_4@#NsfQx^1!|j|u#~ho9 zve8|ua&;QNogX2qGmg(QW%r0q%AtW%-^W~LFm?x(-EGT6o7EF=yBy3*%*5ObFhR&H z-powa?cS1I>GI8^e78Mf2rb@7GCB44=(7MJE%n!pSR~=cWiLIf*DWVIF;;xHezRYq z*Z4kHc4iF=w(R0}vhF{#Q@MAR`=tJUg!NlSEsn}uql3s>F6wCUT}@nf7NC>NQvdo* zBLcmYd1{BoGG(y*&>oLPvSqK)E(azRDA%)gH!8{|0Dta$K26`s_37>ljGM!w`yT`n z;YHt@e$pJvWv?XngQtJ!Xd^XiHPzsLoA$WIfoYkkZ*D7BUUaiQ=SBZ?a$w-1eD)uH z?+@K~W>S*t^A-(4`@5R5GviiK{L2;lDQ9EFM07>z>{G15UohH^|KonR?!Sg+J6LMQy{$NlA|_KIN=%J3m`K)S`sjwuFnSv0$rT1| z8HF%SA!EeZrG4nnRuo&FzIDRyIuT+J0|40 zcT�IjG%R=sM^2O>O&~%HwxOzc);@H#q@92oX#?Swc=eAzoz4q=bT}ixT!DCWGO` zOIS1IgirbFSf|CEpY#zESlQq%6qa3v$uo1)@rV@$Ni&XL{I-dG{>3F+b@%0hh0IV- zbZMBES>IC-6WMiwJ*sD|HU+A)0vmUA|7_gk-#;HtDB!2hoPCci+tPB0uy*ZLuwuzP zb9u!sbYzUf6FYKYc zW)N;=nUZ|mXuCHz!7G%ZD0LiGob%qI6T9Y%cXZMdH56vE*Jd>H?_9Oh77~hiULi~= zNNUHRf(3K2q3FwS;(;Jz6;=9vih=a{FRz2=eeZeQQDiq1!@UQb4C=}2st3jcP6D;< zy4K%`w%(<(OH|C{EN2ijFBAEY_Eh;F3RmxWk3Jt@@gzJyOw@|1xHx6fl46F{$2RC! zRVRJbIBjGJB~g0%UtR?le*Hu^>s{Bo@6P|~3B@z%0oClGOzIVPMd=J4iq-VKyz!Pv zs=`WIio9u#UukxMgM)+9PDr+0cZy@qRkGe?z) zs>^zc_DZi3lE&V#;L17TQRBh|zd1+8#YiRrw$&I-Z5;2mb0B zcekJY((84t7+4Y zKGKrEp^TLE5M|BM%ROdyGcMBuYi5Di*Z*dnZce zebK;YpLg+D4?T~XU3wcs?&@xU)70IwL^uV4F^7OJ8*_)1bt=q6aT>QCY1laC#D14Pg+?pjsab?dz*X~Cx95r>ny z@arcPqV#J0`KK>^tvQ1-sZVprLw>3L&fIS<@L5u<=3Q0VwUm|&e@VMjGbUgddOj8H zs@=pTu>~z{BE=|+sLYB{ww&>OGgFiLESj}a4r*t;vYpxbEhElv(Y>5g@Z8V8W2YC6 zoG-b!c8VTV3If0}a4-aVHeO6`(aUVuSiq_vQd^apkssi~nR5semmqvL)+y%`r361! zm*Xrz0`FfOOz?1-7hGuQrj~O)?%WUDYQ(Cor&y5E_IIbkiRcg5+o&o0>Y}Rq=m~{cbG}(*_7SEWA`>-s0d)LJS5-x6>5&DXi$Yk34qMPheJzL>K?ly>GUuSsneEOO4f;BfcZI?Dv)S|RILEyExLB6Z&bi+WpXPo2Vp zssQv zpW|GrPhkO0iOELIjmk9^;0(?yL~p#&_d1xNmT6H;!j!J@ybBN4ojeQXPh9jGGeJt& z^Rbl|6yu;RUwboQ+r5L7#`9Q=dPEV47~t4syNKRnEaj?7``0I8taQSK%m*DVTNI}2 zbDW@L^hrfKDTS?SzJ>*)T z$pN6b%e9`G=#vxA#Z$6;e4VP+E~)ySEpYuACrVotp-owoL8FN{iz1Ga*>IC%Il-pa zkF6A;u)%=r5sV^UJ2?DzPYlBSkE0iIXgbxfs!aal_{G#SeG#So)KgDQ=>WUd=5#jq zZmgQGd)=Sdo5ruovh6px~;>GAa1Lv!(VQz8TqDgMuyko@ZrN9`pL4C^>_h~#* zz)YppB^{-1(Q07}E{>U_&wR$foN4zA^nD?tvoK(jW)h8ss>$FrWw`=_-)Qpi!FOHT z@CXWi;)s9k*Q$MubA!6FxU6GeIY%epaBU+4*9N-VZX`;_GlIT)xuD{6Y}G>2p)Cx9 z1QV0@!eRBFRSKI?C65$>^w(Q6-J$SqWFeIuIEhXjWm%H(q3S*E-2-s_W$PxrO_5Ke zM{r7$h(M}v0ivpHRzF~EhyQLXz)yur!sL!peoWwN#i`AS`N(acD zRuFV!EsC{T=Iq`S5ad$+S!<;c+ty#z`h|jJENTleA!tO|^4#k-54%Cu)tgxMcUER= z$)TUuU$#E@?&MQfmi#&m3$a$}jCDEMx7kM)6FTOE_br2KFI@{CKPx;p1wsXZPNEzX zfljX8fCHU+9F$yNSKX%&)E1AL_tUNCbyw${iOSV!p6_;@eK){K2uEgi^7|EuP~KN_ zFD)n2OiBgkms!7hkv8)p3&HU*sjX-RC>UWvOYz26-1H07ch)VdQ;O2{7Mo<=bvv2Q zjR9o&;(q5+G##y^Y*EZy9h=WH%Wrkhp!j{$a2*cot5xdH6JD|lu6wqRhR&7Yjoc8Y3fhow03TVXq%JvP^g4%8EPc zyxBiX1DmZS)C3!ae#69^Trj8gE^e8PjFsQ$%qo@3^yStR%9qb`;|NWJIoOFdjfAq3U8atN3$4+TemChx!)->{ zj@!4Ys*d(hV|a~Z1p3qo()Q1M``ttEz}74%VIUz$X*s;p`x>q1X&8d2*q$D2?T(@k z7L7a&i$$ud5F z#|}7a#r#SUDmP7=h>%bW#&7qkISpe9#Z*3jnL|~DtCWJYw>NV`vx3-S$Q{s7_@bq{ zh#1G^{4|x$mLouJ(FLl?r#0_IZwA=>P5t|^N52hjxbZ)N?_Y_}0(Xtq-S!B)y!d$+ z%-5&RbvikK;Sq$n{ZV(RysxOvKOJF!)@(HSo)sqhTOnpJ5S^;g?y}~Rk@#ULvNE%MXS{hXC_dlNj zB5gKZ^Vvu2(NMr(1A+4RJtM(K_vO?F3>vPeV3MMZJkKp_bnONoJ#WON#Xgy|MecJJ zt^vQ&mN~Gn&$^j-l+gOkL-5GvU6lyFNqzQM7ET_!W$!Y$FHb8d*Lw5ViHQ-U73Z~) z^90W4?Q>r_PWu6Kx>NHEbI)J}6|iRYI0Fz0ST!b7Mpu;X_R>=fTsPmkDtb{>a+a(b z2m(0+lH(-dkeqKx@x|tmT;!Ov`F*2>UP3CFWkbuB1P^ldcp~YiWRBZ1lDn&;kK=Re z^AFcc=T;3811Jc=!nglwSX(C<>!E|1tRR&roi&9Z&7iE#WF4Zw?UW2zimeBd-==h4 zWiMt^N<+cU2d{8-eBKtC-brfa|&q|7QKKKHx* z&IniK$nnl~fXkO0Qo$)@L=3wg=*Ly!l-4XnUfG=TA*VECpqhwK2zQR}=+ z{)vl^^az^h+%y16-^$ohlL<~QeHNF^+frt?=Fxo#R%l!{mqnIPLP}9IJ^lT|ul_jL zpT47G>eiQ5zUK-Bpc~3ms;Wre)Q8Q6xo>@Y=8MYNl9CjgeDM!&-!m{CDC>*txs)3Al6n>INhIHZ=Gq^TDqZk24q`b(1^om`dJx7oNT75(CdLF12z)6q)mkx(wr zyAx-*87Gt&-=_D|*Y$noJFf{o`;f@!MB4>lJJF374*ld$rX$(2EO~<@ zJcx1Xkwz*IrV@3e5;sNtc1;JVP+&{>-1Fxk>>4(YZRcRFt);=WE$l1RIr)age4zoE z<2lt7RHePMqb88Xo|apc68}5*{KKs=tTF?FbO6z>@EyW}hQ?pOi%JJCp`LPv&(f|w)Sg;oLCC|LJluy|!E^TpZAbLo61%gy_Ir~c& zVK}5B5*;8Ar`Y7;cMN$!Ld)zUb^qNjVVUk=8T^M}k?mI$O#ii17Sifb|e<%57Q_zjf z1d%qA0-PE>JnY~ZbI^*!uW@8Q1wS&Wfj%@*_IU{FL`#d{_ZcyGLnsi6-)DXY*Aw5A zRvJVn5V~k_8GB4hn=$9cRK*z7oQ(QGfzFERZaQzLoN*)^zGSYMX!EL8UN0sKO!cTi zPfyMFv~ffvW3kX$NpdLR1OaA;zi2Dlj0toa+XKahf*=qA7`%6oLM)}q2)=R$mv{CZ zUHL%YaruiFIIJ&x8SK}wAYE<+X~2$5#BkG@8P6lXSgx^8;pzQ3Fz9IcV6uSH_0h4^ z!J2=4_Fu35dF(6Ab)C6vu5m9A=lp%xY0kZ<&jUX(QE$=9AK(9-g9~)TK9zrWwujq& zy}nO$gTNpC;Zd+-(Da^ktt_;8P*}TpII1@^d{)GYn)KXG46f66{J}p6e~<4eY&N1( z!!#U5wue&HxsEbw=qQeph#Yy%E)pFBfho@!-;a!D4kDWogLlCl4;Zl`MY)+TFT-%+ zM7SIX>eQFct}N$Nrju=N>Aq`aoqbkPY87N9rR`p2Fi(daypPSv&NPl;hyS7Wxnj{A zj|CF%#QM#n1|^iCL&LFX)7Yns(*5PGfBEU#6JuZe2@hi$sPP zn6DBRrZ`uQ6bWGc4EtSxOpuQpd|qI-{qukur{nY*Liivm!(oiYIBID9aGMrbYX=~3JE5{KGCUJ(Xn^~(EPg-?=l7sXs3&tO|?}(f{qU~?{{hEP2 z$2#jzU!Y2JBaFbivZNQN68Nb>oD#xswiV zWG%-ak%|A^vuQu@j;rC4e|e+ZJwr}rV(&6bPtv=6!z>e}?O0EbentQIpT89$tj42s zzokTF3f-cj_vRQ1;(BhyHaK{` zi=HMyYy-eJS%C@i;)Dd#AD};Tm)|?vHVuuKiCgg;X~|Vj8kL!t(Q+(DRM+(PJ(tMJ<{7A3ChzqO?VkDx=27Dga%8O~RquyRvz2 zLkxBZOTlrt9PLg1FEV`6o| zuio0Y#`J2C_19Mz_Onr99$v;&A=Ar$7ZIuBF^AjCY{_#!D@AG2T3Q+t8zb_45uV+M zm7{qm1XSXjs%g-@N{-`*5S=@;&}CUDKvGNSs*Lv4Kkwga)4`$Sa)#0LZppsl`ZZ!m zg=Mp-%h>5(Tc8x|81y)+*Z#pg)VQ>Q|xtMWZ^i-;MmzTV7(Qx#1_1tL-wfKHg9 z@7tnD4@Y#Sv94|(@F*+ECXF7I2$E7F_+Et(v!V=Co<*3Plm#!4L2d zwy?Jb_tpgyM7#^UiXxem8V^Midc|lY%8_o`BK38QH}g8iVD=<=f0f#0d;l!D`hrt0?v`_B=O`jAb! z`o{m%1=CN%*tDraEvJ<0N=NkD7oL0+_n2GLVkfdS=>IN{kWV}Su$Y#!2nOgYX>GLD zk2p(=_BWNBQWbGXnNw;V{Xv#_n9lQUSB0wuA3kEwmaR+Jno(%dIHkLjIGhSGJRau^AoSR{eSGBK2nhvRm~vcz zvJ-PHYRHe&qA9e%w1U)44;_mXVcDTpkSZ@^Y5xq-^LCY=gf6wL(=i%FC&WrBS2;YZ zQ#ov)7URrwwX9ZUeQxRJ(uH$`_*3xr|9Ff^Dq#DKn)Rd4*+;(+kI$(+4NDH)U%Ojy zf6L#I3(vCUZ-n*huGXScPh7#I3e^$xmO@k8|3pwv-{Ae^9V6WI_E%keQ%eRg$tex$ z0hPhd=E@6N?H1IHx=)JInP?_1MK+6nV=H)!-@BdE*sh`CaK=8Rme4!hNL*h3<#mTMVCikyp;SH?*#UL!0Yn=WEtVlfX1GmC)?^$Y`!-ci-I(r@GU2u41 z#mw)|V8>u{$JAwve2TUzAJSBv>U`E1Ta5e1-j3|{cc@E7hDX|An{3cdTYm$hJ<&fqJX;{l$y##Ac(KE^6M|EnjI+03ad%NSl;Gp!P9mPQ(8rt}vx z)>2yb^=L5MVQZr%LUpuv{4#YqkYnm|j9vhEK!?Ayh+fItaw&#NjK(lZT;d^dj4$NJ z&bUQq*x>@#ZXT-cBvL3(5!p`ym^+RuT0h>y{uw6WuA_xH-GII zQqG%aZZBHl*qeM7>m2q;be5JESn4o0jTn~+K>^h)SEeaA%#l6HI+2M4Ujf_ISd!6^ zwLW_K&EhgpFj~Woh}t)0J<`JRgSR`u?(5uhK9y(=&Qe;O_&h6euXu@2uq#{vSh}yc&QYMY=(*f+_h9H#OeBZRBgWcqzbHW;CTSp_ zjZ614Q%F}^(Is!v^wz31jP|Wp{J)7 z@>gj^G)KpIW;|AA+ks95;!p}@?J}GFO1ns?1}~e#jYsNLim6nPO_kM%W`ZRolt2_U zMnd`T7~m_@wE35*!e&daUji%DY0ots3Z7NiKrk(iVfj^gY{ zq7gL{lr;(oNV0IoUaw>sJ@Ng^gR7tnL-Hw+aH8$R_pk7wk;M-xkNI)P5!2Ss5QN(U zUq4^FtTYln%*`~y(bS(=-p?GXQz1C~i>!0ssR(Eos;FKV{4c+Y8mwq&aYx1CwRB#| zGj*L@jAAj93TJ^mf2Bb_6&*BLY5Du}E<8L`b|~@pqQS&mQH4o?=>@y;?^ZPMNQ8<4 z6(U*eIY|i65}jxDn#-Wc1ux-o#;CX4vrYQ~j*mYn&fxwLXXW*#A@tQ_$9*|Qs3+gv z(N2!E8%r+GNLFYpx9n1v@WKN3&3lyv_&+L>tp6l}ocJorr4-EPY%!KZgJzog=SFpS zpUT`4yYF9>=LcKYo=o@2nPyfy!-8e7>NtYTe2=*i`pXyfhvOp}Bop=P2RwE^Jo&_Z#g@NgpVPA6>2P4pJT6$iH!tYbm!_?qN4;}d@HdHCb{U`}DHl3z(p7+5 z1mt$j7w>@M-@D9R@%5Lj^J1007w0}t2wP+I9ENKzT^oG%@o1lqoqmhBw}C=1uXRG5 ze0X!Q49AvB*-4PqHy7Ml@ccOL9t!vNhsM zyks=l(|%_uWf?64FcRuu9Oq;kU5n#xalbCgyMw-vKix1m;(~I(>#b6rKDkmN4H*M& z3EqoNPY6+^v4AGVMv(gJAORaj_LsMtZn_DMI_juNtNUPq$*x>saw_WIQSGO1FE zFmViu`%h)hK{hamFZS7IA9(7ir}Xdh=g)_oJ9olt-m=+pqe`W5GA;E-s=e_@0Zbg; zu_$-Ji{9FFpB)c=r+m#5=uf?FQ*(A{728vHpkG_7zaQX?PsRQ$3a>82=2*9@zj%A) zW2ONibq*GmwEf+wp`$wsUS0M-hGoZMSz3KNe-LWSjSbrD zB|qLtWUh9X?x*oN$K^6r(7aPQ+*669QyfyyHZDh@E=#oQHOanq^0Sdu)xD~y5oIX@ zR0qoz_D6MLf}0G*M5XI21c2ymc(n05?O3r2Dk6ImA2rhYjUt>?lLIQc!)@EPx!-r} z*a5SB+pR67RlcH~Mzb-Ih8aASZ4ApVNArdoQY0G`*$}%#+xFjlr}DBCw1U7&U8rPM zRf~-(4k>RZzHfP8k#v?-#`ri(<>Ahjz~b-kPW@33xD$7PpK?Jr2G>NESo)mB9-TY& zT&}T#lLCg6&8oy;FX{x@x_kWlmg##Vw*(fK_JS^32r>ky8lGX}uxWNhJiQk^`>_Ii*$n*Z?=d(Z~Uk zDmu5LA_&(8`}~(Wl$ZI82B16d84ZPcRE>vZ)i2k0qM*7K%V~Ol9qu99#^O1qf4Db~ z-cO}MteSW)BxaBM>7pmH6D;w5D^Dt=iIx($IHi5whqRS8j=tyAr{T3OnDFNv^F{eW zxo?nA5+)M}haZR2(&C(w3iR{@UB$BE7+PuJ>NJQZ@HB$NtGwrLHo#K{E))^;T&KDI zm&!M+9jK>%pg-IDx0~RJ=N;nuVRPNN`yC|WtBJ;$ zZL21;Zuwrq^Gir5CEjS&zP+U>1Yb3=TDq~?e0kx={|El{6Nfs45`BCZE@&LNtir*6 z!HeGthduJ|Ff!_A_P@df~ z(>(;|&b?3RhhMX2LlM%6>&!$Tp}I@=6Sw{S+n>`$)P1$}k$fkKd258J3NU1zPfA~A z=BHAgy{sF)_hHY$DNPAWkC z0@oRRMs=XGrrBf|xfOu9V1=f(rw%+!m*db&XBaV zSyMl=?K;?}5TiU^@At^P`sdc?AF6#=bBn){Sg7vS6{WFRu}c0lSD>vZPu1%F>Frye zIZP)J5fjBoe5r=AnA-dwJoyb6uAwf2UzV4v?Qj>&ue@Is3BzU`9a#^vti0E0 znX3|mp`|QRD&co2S&Qh$6k+wmhR4f`X~YSZ_cdTG?G)Id*oumNFbmR*M#6QhcC+10 zRL-WfqSHdWD{0A;BxL2XkV$JH@56ySDCqlKj+tmeAd>XNm|^Qym}R03%cKBYD}V91 ziNF1Sh(!K5lHY1?+F3|N{Rp$LH8OBQ0b?BDWCG6mtelC`*ja5^kM92xc<$p5xbsu6 z6B`|LeeQjH@yqv2hPQz?n5qT|pG63mr9L4^XxXM+>d9<|xe3@p zwAYn86T0fs^Sh$7W0T1E6`t5XJ$jNL?NLThj@HdSzej?SES<^2%ClEug7y^eVO}GP zRtwjRjj!rcdI?;)DD$-vGT&sAey8hn`aBgxW14-2botkbC31NjeSTa8|FqRw=JMjJ zCgJCTjgTy`@Yz@%(iCCPT;Y=~+Eyj$;oTeM80lQdp^v?01j}-t4LQgu&c@J$aq`eeK$- zOpqiu$le+XgzdV)|~xCru5! z0X7UPdLyhJ&#~cJO5!C*4*0$tlLx*Kl{K3J6wJ~)LJ3ag&mD;ZoxP`K#3`XDQrja> z4BDtb2@Ar8Vpm3j`p88L>i}axiply4m(4>=21nC#1br-=Wr^1cUsh?QMX|F1Ib#q- z>BZYEZqVTU;<^}E)Z6e8^G1HB6gA6;68SS2&^)8bG5$o5DEyx<9PI_A2%!4Jg|G1g zTuc^0(UzkD%MdINWkv&NT$r;lk~p~ z-MEB;ajHMx?|8Q#pF{tiVd-;?*vdSoR3D#}0rl>@_8gS`3BkB2efNUZ`o1py=aYl` z{LGhLr+ZH+m`ufb(+xx6ekG!t!f@0?~-W459oDynxK zWM#`vS*&XU6ioqMT;~Me51+{j=QGMkD1&_RNGOkdQfAN)NGNw-0TQa_L}gukUxkEP zdT1~BT)W1S!c0fzqO#AOzBbDfG&m{4D%EvblzYy7&r}btI*j_rJS%OcNNXK1Qhl5(T3$>M|-P;acM^f{sAdU|Y1Qdp%w&qwR} zJj{vkeTfaA~R!ALKWP~EM|DV>lhV^zsCXmak|R<@g;G{Ge+_ZWtsj?B>m z_8u>KD{OzT9DP6k#cy#hTpXQ$>(hO1h6q{t>JIr|e+s|;(KkzFE_l&figSI}3c}_3 zg(?ZYXrl;t9TlyNTfgS%MgFG8zh_wxJ!*2iXMuHeWTaknK<2Y!j(wZ%ASmbk`QN#u zvlj?mV9+MKfM-M7apMn3RxRco3y5Cw**DGl81ya^w&)h_(t5A`XkOM)i*8K zlW3G{&6H6|*Efr^Vq3Fua7-4s6D%1Z=9C&yzPz|Lb`Max^P_Wf+4M}}{PS@`C6@?x zTOh%i3WSPR8JfNXjVvi`d`|BT6A^gANQ3g44MS~L=e;?E!DaQ_=H4~|S|o^N))p6p zWyLa2u5$Z*ciX+Jq??9D^)uC$wVoc&+by247C<^nkJ8VXbE%^;ZKZD0TGC5H$C*g+ z7L61Q-WRk6Z!NhP{|3lpt zMgR2e23KEUlt|pfvj;74Z7F5;a^u!fZ-mu1eIK@N-3t5eyDvQR%ro6iVK#`;YSXuJ zsE2raY}?S7Uh%lZ>n~g1aQ}~AczDC_Z-2JW=@2bQ6SuVEH{UHS2c)hGqrWwhWYd4T zNNu^1AYHd{xUIp1qrp{!dKoQV*jgr+#LY4{or`uF9nGB}rH#bsF~|Oi{{6<)|EWd9 zF~|Hd{Al%mfixWld8F;lvd=4~5&%Tkx2A%%s+a7e;2d2q8J6meqts)|WaX1ktv9Ml z(pUxAs}<@~=^7jtt-Z_h?-T~-Rvo`PT;ZnU*AqIO?$smHsIDo^XnYjPdr0ILb>Mt* zXVH{_S`-0hS0wba&C)}X{=No3+s#GVY!kDG^~Xb=o#5&Td-1G$v*=v*dvaE+)$A_- zn}_S7eW~V+S_IXgLk{{3aRIf2F-8cXKczC*Gv$D8YEtX3-Q(mvX_1{F$0~XB8+gQ) zudLj?pC3N^SXg=ZbK&HZUpt|Kl(sVl=9G@zc3&Mf42=jafel7_Mq!1|jOh#tRS-Ks zf|Sc6OKEBh?uyb`umyraRYyQ`!#T7NM`x`x2&Kz^a&p_}d&4ULF1_^9hWqT_|F)Jp zfcx*iAI|;Xca>hZ^Y7Rhb_A--ri|5%7NiNwVIv_As@&l~BMGA*2Eam(Mt>;142z;% z5`QEr$*QQLDD~Ba7zM$OTU`iJ7ALE3{6>_Y-U=BKjx}`LK+dw2;->0g0#%kp96%Fy zurl0$qcsO&L8?-zOI4&vRaEDaa~MXNmaAHlJ=3si=9IcmY^IYmr&JDg%BLlZ-xDP} zU={SghzV_*z$^GDeU*^3DoTlFqjWb7!HUImgU;V@b9_G-KG28T}acl^73-(;h%H)Gc8M+g?%-+H}`7OaVu?`Rx&CdLOicy^D?1A zNzSS7yU|8|=eDGQMSZ@UhGW;1n@BANi<+Jl2VR)Kq|3;`jgA9mDXC@7X^YaCXi8 zQ*Z+%VOfaQcdQCN{?NOwFKG+pw%|cu=Dsr8xD7uQnh>mY(M1 z(dlg!1sjwVM9Eo{HEfQL=_~QOB6nUzl1#YD1q*gBJ53X5Iel%-x^)Ghm z@8-|Vz~Q4Jb0I&S0c$;wJvOK93k0z)yEkwh(0S}P4u^u#PUUr!ebo7{v-lEIAK*B5 z`Wo^)60bvc2~Ih-pkem)2~Mezp(?>C)l122&&hMwp=rZTW|!#gWlJ8Xan)c}DA;l( zD^zewl_vw}?;}pB?p~cwX~Zc7&p>q+>ddB3<#Wrjq0B(loKovrAUUPl%3ZY4;JH#d z#-je0FPUQ`sX*pPVc;yCDx8R(y>gGXEht*VG+26_2u^9&+Br2_Dt|mSn5-OmwecUal)Cp3-(aan%-Y`1}kp!NpNqyX-#iSP@L_$ramDEh) zOucxXr?Sxc%yL4_eV4e)I5tb?_#BG~fvw;zXC4JBmdvvgdN8g%mch(@btY3UD;3;3 zA)y>6RVl}H?y^c}sVG%#fNH5pZhnLYR+z5y&@szoTBcSB3u(Nq+c@0J4%)VErl6X` zm-IWa@xOX^8nD0J?nWaVj(O!A;9voI*JhiVQQB5Lw{7gtdv+vPo@L3 zf;8R&3#k(2X614RqH@Qhjj2|a4_o;hTRpJ#X;PcB!f2w@4|i-BOti}(Z5i+U0;c*6 z>~6cem?aTtEUVS&a3fEcl)V7bemN@1@Kr${K4c@yr)gVEAhg58b>V&QF~4uxwz(zq z`eEbXh(Prl;?{b!$EK z)v0s7WwM2bXhGA5#z1iZAYX!SIwe1@n?6`;D@(abQ&y z?Lr6uzEctVdz@U54x%s=sGq2JzR+Z1$Ub!(rYnzaK^=nhJ0wpY@ybMwJEK{4oq75- zI5J+i(riF`hWq(CAzF!NXMzg>LQSc>RDp6tkce6!!*Mzkc#!1$)X&*t{Ny!S2uKM_ z3XmvTuv~5>tXHcEAV%gIr9~5j*YmnnL?@R@Ye0+{o$H2*4YUV(WCD3`LVw1<<*fsU*;smWPd{KosIl}>G!R}H zL)V7dhR8>%O`3Sn^yhwbg><;O_%D9Ku84u@-~820&h-z+e_!$MXPdfe#sqHq59~NJ z?E;dUk_*s>Zs&BUU{Q)RAcS2AXREF3_?8FJg7mH?b3#)ah?Wrik)CupPPJ%SF0yOcL( zA>*3Au`F!UobeqhsI~#KNlK{N zvF_8x1Tr}o3ZjDAEOIbxLYfxM%mcLvq@0@?z!VfU6ywa}+f_2807m?1E=~ZuvkOyQ z?bnoc&w4JcJ+XX3Zi$%ha(+`j(#3)$g$ob$zgaSS#vDF;=|A3PPUk-Vjkho!%brW# z{WDc(F!WX&B;8ekMUKf6{)nZJyFLw_)WV=NKNy9Oero2P%+=6RN^)^~)Qw)8`WPGt z&>8fOz6GEP9A#_Tl5EYMO-1E!G(KTzbOf=#u&rdQ3Np;xP0tqDt6ym|337zyWb;D4 zPz+J(7jDpibIYN}8TFheHl%_pFgYlMHq~3Xh63LEIuemPF2QhWiaz1WDMtoJR&Ar4 zb{Mf?GOnvu$ccqc#kHrDP~urlUzCVHZ{y1|&J53}rkg52)!3X;n^8%fgtn|z^=?I_ zLwQJ*eU*-M<@1yl2oEVHpQlvX$`+-kJvpktz8M-GPmtnkfY0f80Z+qDlBR?@3V2RH z+DS8AGh6R-wZ_H9(Rl6_N|F*vZ`ui^6Z68Ga0rAup~I9XnX!RHIHH?==Xsd6i;%a8 zbrmJTG|KR|!ZfiZ%>zi!7V^(*u$4c+=e~XhyX1nKjTYD_PrQL-gCDqM{Mya`#@=_< zyE+rRRY2)v4TWnxo!5YTIw!}zk%eiC#C@BRpsGK`-qZo4gg-CazLB#Eu^+u-N0}|# zA7ems0a|bR)roB3n~!6=9{+EX|Hv3K0I0VtHLB8~NNPiCC4IF2DHR!MFopI>@S7?Q zLfRh2naI003HmFEnrrQHsO_fT(Pu5BAJDe)se2veCZ+9u_e0gdvco4)uYJG#b&l?* z0f?H!;2jWg+LN~GrD8E-I)OEaQPg#djxMp>0b96(eUq#Lar*PmPd%V_-V0#{1D<0& z+4~T){x{V&h4(t8#w(^g3i1q1ZA^^CTfSbL``SC6;nY;|^57;0v7fiFujH<=en{B( z4o7>&E>;y5@?PL6bXvUDSmlX~XwhU1fiaIu#`##^ zyl^$iJm9{;b7oV^^gpzLkXmQ@Zl0hIa|+;Kxs-7?`b5#05Rwtgl!-k0Rz4a)#SC#3#!7%q8o-0wp)7k(dQbK^uNDl;eUF=tG#ZDKfm z@PFUHF8cH9*a!anI@9G?dZ8sXGR;za(VIA>3FEHh>v-V1sl9nhYpnG9f(Nc)p{-eu zNRcTZHOJEwk*Kr|HG(D#s1$bniXw`W{U7HVRJm!OuS_`iG$0)(E-uPUBC?VS0juC8 z<(li02f^&BRo_uhfZ!w5`6Ey1CGYr9T}^c3SJtt&yrlY{5?Sa%EL(cO|8{|r5ghv{lH0mnOV^BH`;)N&)x=USxepsB9nVlJB3Wm$04{6;=%oTHaMEZfGX zngu}E zW-1X|kk@sXRGz{WYB4Ey!jNhXRKruM2k2_@0J|he*ZESZ~H;ZvJA>Il7;Is?oY?M}l5x4XNJ2qmj|#dEF*r6X!G_26HrK zIKHbo&;t++DG(6qfgDI%-(WBI7s*}&%gYBxL^-R~qOgaz_2TLTuaemBPG>DC%I3>s zAZkKpla2g8ef3R3o>J|v=`U_I0w%yh#2k%r$Kk2XHKnbbBydDBW|t}?jmpW7=p=v| zI+#S<%U9c^CT*#bWf*f+fka*)u-rAmS#P;O1T0J5--L9-4L8I)>u>}v4Eu_L8e`N` zVde)Ep!MX5wi}bqJm3O!zwLaDwUh7s?z%*51}j#`Wv_Wcp3*nv>@vt$D6(Q-V;kPR zrJA^5FdnOE+@v9AMV}@rWY4t^*SLKS4m(HpO_sfz#uDRjG1`>-TR| zbj3!O?x{p<|5+u&_m{_{;<7823()(OcYj)F?QXn!U2t){?BcuFC%<&6 z_*)#=8;?y!t) z%N0TU(y9b01(@Xobj>PUtO-VY;p`!dXD}Gaz-wRaaSSwMsLRx7_zQLW zs=u*q)^DDWG+E3(jucQBW|Z=@I!mCT(E&=XVEX&>Yj%+^qs@Wrop|-r7tA)oO`3m` zV&|ujkp<1ctT>%<14TUNHAT{(Huq8EQiMm=WW+;Y&jqsLQS~kA-+OC1; z#mNdF4U(k8LwP9KH>5)gpC^WnZ*YWs%>9M`0UU&jjRZ*S(_T9Iz55G(Dlv?^L z$y5p|dKD;Iua(D_*{%0i9Lg^!bYw_dfl>-aeOjJ$Pse@Z7uTEx&X(OjTGtD?{Ii9t%kB? z#z)`!{-xr(pZxQh#C`wpf!obGr!OmB3V*fvEOZ_H#JS?7O4*c`mpDx#B4;6}4Fd z5S~)??zlZKeRzlIx(1L4qg~$th%+x;`mG&oGTfvz8JYfOSKMr8kxFx>G6@9e!vacCoT=Lj91< zEsGRgD1%X^Ax)QPb0$G!HI@zQHjJ_bv$``IXmD+I+nN5=@*E;lkI#Mm&Fqp3Zjq*3 zAWtdvCIuorXTbEk=yPrMrPqc!Och(*uC!%9Y2Hq~^4hPo@QPtSBJdHrQ#$eLI7SZ9 zLusHJKHe|nETDY$=C2Q#Z{Pa9#m-&3E0H|nZyMUX**qMYpeKK#YUhiY``>-H-K32v(7|-*Um@xo5vTH6fDC>{b0q|Z!giZ6L-a1}Bh}`rWPqb9A46l$ZrZt(8-YnQWMrw< zxOSUOm45;?9s5cH%SQ#sRZY80J(AwSUlr_ZjM@^SI^m%b_Y@(L`EDFvj+B5-wI z4Pcm#rnHkFH5XVr641`lbBE)cY09q{PhPd9yakX?4gvfw*{tOFT<)NgCegDM@!vI+O=*ov`a zc&+f&dfPIQvo{|6xZVvFJ>RfQ`mRjk zAtit}iL8v_DYBWH{16cHX-b|CDN~gC8{+1CowDKITp1UjA2o=$5zt=jdL!_*51b-S zhzdj#D%mxv!Z{3qZ%9*$k>2q7+6^NzsE5v5Z9>c@L!1DCeAe59=>Eiwf?*H|36(sO zl=gQAf3`O$4evmBOO1@@wxj1~A&3-`noN02ln{EF@+r_X{Q+Wp0d&>pvxK%21US9v zYlC%{UjWh^7~`g|4b=_T2Ih6y1w>Wu%@-^RdhlQNp}V95l&08Ahuv^jPGuLxi&ypD-h$$0*wc8hra7CHz_aMRIWi10;ytmfb~NM0Br5IQ()0)4i}&EYf2%@?*4}4F z4lk+2AB66U3Pr`R&`E8qDZTBE8*12trLv081o&+tg@no2E!{}cqdY)c8FiB|m z6cTyMdk5G}R}VH;bk*)RE3k;b(cwAG(J9(4OWSto9WLdi(#{5FynB&ygc?kRv_mT9 zx*sS2=uiQ!ct|S=OeX*_9a74v36Jv-Tp3PKt;s2u!rDN`=?;=*CEmQlV^sov?b4^) zLB^Vwcg!iU6pf(P3JL>P$ukuwmvEHlKBOg!E_XRho!WW?`dVNkFx8&+nnuL|>RdZ@ z1!$p|rC6a9QCN>goSb~_M8EaF-ylzEJ2^;Ar@G4iOhuawh%GhVA__jFCJr@$y6#*7 zQgK?MHkw>b3gqk56hoSj-+&rT5Y4r7DpIV)n=^Wy=@|5WeP&O2dxj!7nfms1OW;_w z$M+6cV~Q@0&|Tr*cK&i_Z4m#^+@?U}MP%iVvB_u5rP1=Knp7`E9&aiaWdVm@HB#CF z6G}9YG$j<;%WAqW{ho-(Dp5DXJ8j>=I>+{{2TGf6ixG&ZINg_!;b(X}DZqlIG~FQ& z9m8`$xf5DDf;^;&BWDM3#9*&qIi4nBji7jANuQ}IP4%r8&}PGve^G@cG^9(O^tkxeYYu?&0) zu}lY)w#wF??R8D*sQd;d$(kw{#Lqh*d&yCg|nlDTtm2XhSN&3uP7oW#=zBn>CFT7uqy3hm@04 zV)Rm(0hES~8@e`qVzl~!3On`KF7x0wKQULZR`}_um%U2lbN5445s0I^yC{y(t+s-$ zFZwgL^l?;-#Xp-Keu4G9_F(qStDaydoN&Ul*&!wCz1&0!f(oun(-vERvIL;@QQ+k8<)S<6ouXyg! zP$!G$Mq^RAe{V@q&qc~sTxv8m?U5c2`1hg(J;osjqqTLFN{Sk(C+PS!{k7=%lHerO z;IcsaO$`u~dj;J`FFS)3cHS!e;iL_>KBVJg6z z1ZN-W@0pZlFwe1P+9n2gcrHR<90B3AwZRswhJthEfZ-7Ez^}KeU;sxo;9SrwK-!^# znm*4#gLk0!Jvz;3iZBQev<)Z+8>$R*0IB-B-;3yEWrhNzoNnhh^R|ADrd9{LpyiRE zRr&#-Hdbh9pFE8X9ATprJ#*-5Rs2hT-a^kq(|9aMyGqu13u=Zx66) z)g3o|Z+x7+2z`bci78OL>i$u~zq)wIxopjvA15}Jix;0OPAt}~yUxs8tXKcM?rFVY znM#?J#|77a6f&@iiR9OY^Sz}(sSiZ$-;Du;&z`@v?lG(F{LmnL@j@F5S!(n+`|BmM zSza1mnvQtWAbav>Nj}iiPk*PV=dQ=3Tkw9b`u%uY|D9aOG^DhX;456dE-wr#YHLH_ z|Ew4|{xrZ(+Ki-mPd|0liUco`OJJ`Si@t8B3A8O^n1{5S4oJZjNMdnOv`@5oB_MUp z@uvd-4%%9Eqdak5lSlRUumB50rVW?y?ifj@iGN%Xnr5Jl%1I$$k5W>#>vnIInO@wIEO zb?(w^CeijAC1Z!@oQdULdQ6Wg!#BRLwWY`LFK<7Xy?)s?^Y?*|ZD3lTv*R@jJnTVR zGD!j0No@j3(-tSlb=TyVDGf-!d{s6e+kMZOb?5B^QoT^GT6GOugdBJ3`(2O!!1Znn z(OvO;4Koq%rZvVJuX45wK{iNRKD1fdGb%j}5uEjwAy@06-DaU6?Q13jTt9N5FvBXE!XgKl7(Iu*(NWq%BV0Pa;r%haH z%J!UN;ff&{*dgLY>y1r#DzyhV(nE3LH;$WQ3P?GTF~&hgQ}{7Mx@o@FR6-mG1t8&J z#&=^>yxkRUyuJ0i*9r3ds+gn56^cL==h5y;)$k_o8jXbQDo(9ak3sMKg5CT@l3TNX zUP;t@?SrF=@=elUEjy+(?Z(EGjbqg(uXuI~8z-{=z~5|S+mGmTHvbM?6|?=yS;y?I?sw1rWS#{p6ThgJFGiv+9>pNbin?T6YOpSC=l<_CT~BN8U~mDNVcJL3QO*M5fm51 z@f%Mcger60&xYiG66tey?i3(DM5W@;t#H<`Yn3~sczA_UVoSkxQa`PTu)N6!vREh|wWrq7VVuKqigg2AOBUCOh zYi5eq{_fNR**AaqD^sTJhtE~(RAkDb`9c5n@<&=)OR7_(WYqXXQkK5#$zk@~E9Xdg z7GdaGukW;MYVvrT>2tl*vVtOQ(X3BZQs>AIe|^RU{bEsEyr9QM93w=(S?Tz~i1__$ z-b^Co#=*z{0e7#5JqCYlVEc>jRvuqwtL~F!9*ZX`+MVv#yZ4Q^H39#bF&OU8h-F_W z)b8^n4Hl@j$alP-yIpxS^$i0}8|~9nJ=b8(I+(2kW~X2<`m!TU7X6?1%afkByt_Ym z{f4X72ueH+Is_M}I=12wH$0^%kI~+>NVr1rdknS7GsZria)r{$6UxR3ivm&sx}Ms? zw!QLb)<3_@Zhv4myX9+A=`er({I(hYkefH9zBRX=Gw~Rdtzax ze&WyQg^B>~lV3iKed5Yf%`+drVz~fgcrDE_V6y2()XoMvYEXH@r`Fj3%u29_jRO?8 zG=4)t0GmBhbo8QTAS3E=Yc%(eQY0em8Ww!1c{4&22Hxl4DLu%9{F1a~-rl)zI!Ot}8~?}-R)NPEqhuLTy0G9el$7@G0${BOu;72aJZOZx_^Tu*~;>uH0RHyL-?g@cnP5A^)kW&zL zSP8IBc}O`Ug5TverQ-n0gjxnkDN;XEX(~-gjlmBI0-MGXlIK5EWscn@nz$fWC@89& zs-~mT(PoOu?o*N52%FJJnyU!fzCuylqqPL6rQyov6a-IcQF=aurMjX#r6plg>PB4= zcElhxNS8jcqao-ylle(IQJlz_Rd)Wh`x9!8gNLeI+CK|zrHra1BOfs{hIP3_;0?4l zt-2e*^~2-lZ{%sFGgHtv#rJ$J2Bw$1`xfTR-hu@;Rj3+%Os@Dz9pH=iav3P()(0x= zfL_U|xo1osA*1s>7|u-#mS*=z+ix@-o2c^CcGqP-dnxGR z0Z3Rw*`9HO9bl6K%n15;Q5u?~oC`(Z$jpIH=IzN;8F&9iEom_>6MEbmdm3ufTIbt7 zeboxlPc+!&RRf4+Ty6vyn!i;8VnN&=F=6Im0WnAr64hsJ(Xk2L_X+t$ zMYv5N!;0dVTRYu}Bk-yY$5{{_@MZ(0oa!VQygEYfDg{&+VVMz`h)y=8oB7D^5Qu*M z>t_U?DRos<5D5^Df~IU-It!Lck=UFq_Dqb>yy~7Ua@@`?OQ)ttgesNb6oG2!(Cyim zzm~n?`A40+etYCRX>^Lm{}ptsDo)urp018j=7?SWz3X+y%I~pJV=&5e@POaOpI?5K zRn(9JwAa1n_|C*^Wlia%b{m25%NuyK8NT}f5||=02+n&nRR1;GZ(qR-k#4VM*yWRuyyYp>; zS}xTeSRsGD`SLtUhdeV}lf~rdH`fcER!!}?iel%;?rY_qYC#}8ue%iPPq7*nhr_{yB_<2 z`0n)6|Crr+>vtM^v3@A$z{l+G*wL-Z#@UVcoycBu+(X9mRC}B1U16bM?Pj=&EToGl zLPu)t6LItr5u2D?2yXi7;FOGqJkg`9ATO&UXt#&8Z7O#MhSy${NRuZWq_|!{#@O2? zv1$JMZ|z{4D&s0*6Sk>G%fvM;le~^LWoI7K9PpvRy`g0y{Vm_G7QrGI?UODWjW#7H zpNa*eoub!+lu&|>N@=VJ-IUNEDQ)Ju4Wou*@xx2^%elTouI0Z&3Dx@Au+XrW-y=H1i9 zS&#lCTSusTN1gBp+g3c970H5UDURANIkKHwHij^_4JWivJhPqKIh8t1Kqh;X((d45y~3JhhEh z-9N%s99K4F!v*2h$8Isga!?U4%fDqlD+OTwuK0H4>F;E#etr#enLg8LG0>stlV3j7 z2==Kw-cRdj8)nqyAw|Bwf~N5bGifEhL<%XlmF55I;)Me>xL03&^`sW!TfT8OI|H@N zjPlZ2enU##`je~I|%(e&tYc^*MOL}(tx zCO~PPf`D`qTBw#&79rY~qdg8pi{D+Bak38}SyX+5sT{Dj_tlce0^R@PA_v1gv)WXsv zoOuA~UM{88m|5-dnf|^m=bDKI5(2WTzGJvl@pG_T+=t^XeTpvI8R~dn0I((=@uzD5 z%VZbKjHZKW4KMdg?KK%$kOa7;T&c`1RL#%^f9Wc@sNMXvAwh)&84E=-B5Zy6s&mkt`;;e zAjR~d{+<|^j#y17_cr?6z&OcuY=9#t0W>)K$A4bQ{{H>9rWWn&3zsoBP?Oqhf_nmp z|Hj6vY!+%+)pb43@cr7M^Wp&&)v3RyVUSKQ>2-49s%9-uohZ zz6>rmY$vscrnDw-4LHvG*Z=WP4{S4;oX>t~&uC(&K%NQ3sHnTDZ~c0f2g&@m~z^(#{bID~_PUXU=d z5m!g(z;bc3HkwW-yu`-FI79RPIU{m`8ty(Q;Rqr$Jdoj?RKwU-vlSdueKB5y?Truj zzC1Co8gR1i;IkP5gc~VmGi!zs&9tKwgdF(PSH9c;A{h}VqJ!0^zI>WuiU4-cmMSZj z3JFIVn#Lv~LB*t-U_Ac2D}JV{t3WCWPCKFUV9CN+dwmMDv`I$;t(aE6G~CiocBO4g z31uM?0Z)d#2=>ZkZTcXCT9^FLPswM~sEKCByE_rGj(9qU9lE&pK1cx?NzO{0Z@&jf zF;Pb(>OGHO?^9QuCO)Gl^+&zq{YKmPXY2n?M$sZg9U7LDPv|U>NQFXbM||e|gA%v@ z{=dDb>^?zh1*d3}0V-;Yqbi?@aVI-anFptDcYInbWp}Kb0KlDn!cm@%8?b#E>f59C zJkK84?-e>TmAAYPc}nvi;dd}=D}o5LyPhl+6ip9DVA&WO9R5l9tYV?_#q?m197vH@lKKK*}XSGgTn`sp`Eta^28y43L+1#_GNr zhoJf%PbhgIrxLA=Qk&Y8hSV^72Z&BB*ly65J3&V7Vn;$X%Cs%t?n-1lG{Y39kkA&e zRE}2rpp7G+p77WnfvF_0r@B}!z4sLYySWZWrm*m^tI^P=N<(>k=KKS4ER3*Mcfs^k z&3G^NLlnt2m*mjy80;H+k!>y=WPvC^_E4qVeRTWi@wS~H7`*E z9+}_-9XQ%XptN0fA28_~vH=GQH%z@f1-5%+!dw%;w8!J75p90I5~fsz3gXv^Nt4FIW6>HqhMoSf{{>wlHu-yS&%afCO6psCpwrd zWH02}iqUcWF!y;%EpdO4r<5y}hz5B|XBt0gD}&k1W2jM-+>tI%DO1`;IVNxnl!_(6 zRjN;qsuS{h@+cKp9{bZQ`E}`gZB(bT-n-b?e4lr*@BPcp4zO=mP&%aptc?;1(4pb+)N9DS zruTbdk>^p8>yE$%;eoFmp1|fanN36*aMXYgZBm78Weg;I(}3Ff!j!gcvo}wdUB1lF z$?WZP&-elCzB^y$eD{V^Qlh-@=1jfs4IOPhzoY-5;5|Azm(-H_Jf#7aVa-bkg+QU( zgQv6=LBxI6KFa>^9dnZXDON+xQ|k6N(DBmcUVk`^%_L)k?njTiPH@kvY7Wt{9j(0|M>j z3INu-xdy(me4Ak$fS%xs=5__a9SXQvJq6YuU#G|LxNApk0+Q>eBMwXbb1U`0=f05U zH9;eSE~m`sFht*}y3o-^sI>>{@a79nX7Z@Hz;625U^xG{O|dQX0+7W++Sp*+hx1^{ z@{80G2L{6rBzzemhF}#JQy}>hJ5e?MWO@^z$oXaJuT37MSAk{(gA8@6l~>0z7mW zJkF`;%%29S2Ro-)g06&EN07&C@Gzawyt#k^mW&%bY z;?|yGsLQ=E$qg;j$df-d1ozw{ls3^?G`z{ z`+}1UC`kg+)=3?E(mL9u5kRVvq=XtJU7j|%gR>uJ94MVzQkv3Ghe{NBoSF$JE^@uDIExHQO}&n zgV*>Lf$2bot>f=@kFfD^B_iVqwxPJc_#U;UtL_^yzz>1x{Y?a0Nie5yNa?*P)hI0DVWn024GqcV)5Sw%M+$CO6o zJ~Ym|$*f~x%4?l0BnEj%Z@5aH5K)S|A7A0x!hhmR zr#K^i+bid=t-pLNTXdM^IDP76uZkCT%Gb*ReB8W_vEA9=G+RPaj?xY;ZDCOAgz#!~ zD>K9ApL@u{Q|lCFXM!X!o!=dFXV!7=C#v#`h1Hz|nD!VCc;Ss*DA*HM6H+osNrl?U zS|0Nszhb#5o1q3$|05WURP+&AWkG=wXe1kdUaC*`V^mpTFQw z*f;NObOHU(u#0#T7Gu1QCJM+!Xt+S9IAOmn>MNNFXwmdY0MjQAK2k*g!~CS&1GZ$z+t^)q{YX52_z@?t zXP*9*_`dl1AG7KMzt`aU(mG>lZ)!>DJ6%?rPHG8II$7;!m>6p24H2`HYfg~Rd;q)f zhieUHf^fn^I<$G5Em_cGg=_q8*#Q+cF%g5(qI7JEcn*AJFbEjHO0bA{4<;nUuLVr0 zHq`*q`Canp-9y?s`Vufk;z5H0NDU9^#&M6o7KA2Mm${j;i$bueJi>Q?DW4)C458lF zz*NQzg^)1jl&4fad-UiFCI=+K7uSSo2}@A!01t580+>0hO;WVO$M9HH*p*)T?Hx6j z*nC*Fvz*MtWcxq6A8XP2ZW-qeTZ0HQs%%CvKt-`Dl57oVa~f5JO{w<$N4si6jm9L0 zDUMY8Bou-!120y@0ec6`BKPacto6eFS#h{n&qeihb%YKgJF?-~hI3*RBpIZAHLY zKOD6aYfiC!20%Zd%1H--6}EVOkNNwqm&$DE{uNe4K#CgE3GPWIiXfmShpO}twRdT9 z{7@Lt#PL38M=8R83O3(DAwfzRG)oA1?^_LZyq-k~Rc)!o zvRy#L#*r}v42x1*NhzU_CakI{p%i75ie;`rr}mDr(v={Z zHNcg#5^EfVK_kFm{v z7}C%fJ3kFY4<`fUot6@+s6NxVcARhv7v}J5CDA zf)LvB2>&M=Ph_t?c8hsh07tErLyZBk`{WTfUZFy1nWO|QJP%g zT}}bgW5xsAxgP;6_uItMT}{O0D;6L@+p;&(MHem>W&w?+4_vf_ZLW+2awVnYuVc4^=h^1 zR7Lp9cljy98J-2$?N`I^H8UZwSUq#iBt}6s*s*F*w=x zec`U1Vq+`X1$k|?6Q^hwxpC!poFUq>RKiVd(b-TpGG1DpGOA@jX&!shmUVV&!uS-F zPsH|;wiL=A1f(?G@sb9o1@@|Aht-aqvDvSBJ7b%!5!Y6p{zq)}>hC3FHGYp>vHI5U z1~ghp-cF1OjY8M|ejo)n4sH%}i;8GbEK1x9fig^08Xg|*sH_6%b9cVP-cVGFMBaJY zz;vEd;Q6Lg=jeXQ7xwAAu+}Qsf*vU&f;^=T8A!;D>H`@3e^Te&IzAH4P-1=0DyH~CHZc@g93Nac*iFax(0kypp!rPzZiicDeiF=^i zMvIa+Nbh~n^w{G2r3=b|nuDelZ1NzTqD7ns{%|}!vzDcLtH2$m@Wino4;6)bwzO6| zi9g?0WcWyguk+7W>@W<_;|J|YF@?h`))A41TVb7IW4kMSIIfe5ssR|Bm~SnG4f2wpWd>=cSa^Pch){V6MD-<$xCf+ zkv86(ASvzxYeOLgY;3$L6v&aHrsAOJtr$0chLmus-8My<>I?Ha=_Gw z{IQ&^9lC|R@2q!qCMRp_6ht%2Y$6&Xw+W}BqfmcCnP1>d3)6(ioO&7O71$j;~>pFy_Z7x|~ zj6Hw$X-BZn-MKTghE2gV;?8{Hgr}4zKr#wxEO5mBXW~G1|5|B7deX`rY%4z$4L@1= z@VBwir>=GK?0Mzyv5_Z#WZ%e@>37*oyQHKa$ zgFMXRj(cXQ*AHRdztH0=)6R-6JyWEe3=^K#brO&5$Jj zvYmsboZ{Ww*iTC*QBHuCtV34`*l1;f6~O{gGq03`mql5;Eyk`}PVNAFKOOSq7WVvM zbBwHuxE&YTF&BRocqhb`PK8brG;P7Bi=Nad3_a)mK3L5kN+U`-n7u1 z>BrY{0`68v`S|?crm;!4S(;ra+Ir?aT2Jzjg1Wz)=vNbZ5AxJ`>V+&<@6Q96YH5J5 zzSJgd!NiN=_YJo_$re;!vTZ)UoT4$T<9+9=_mR!b>)8(0H~Ipbvu7KdGqR1%t!%Gr z@|}3vhg+I^1;!)`ua29 zGa%QEav|aLH#-KR`2FlM1j`I{)Qeu|E*04LL^b>2&X5hJZHFHnZ05-_)wMG3dP`_Z z(>f^I&NQ7p5uG>inJ=u}ZJtG~8c>HEvg47*j_Ug0sq7yvy1lOQe{t(1452X+qHn$B8+VJ}S6_W~!{hZ! zUzT3)$V+I=8szW$?rS`n`k$TTcKC^f9jt=GhO8$DOoxjHnZN(%fBvWO_q{PWq@;7Y zYZpqHO8qtkNE^3diH!hNABm2}z?6E=+x5}5DX9J(q?AzK+L5^;ql+4H_e-(w7UP;3mEwn?lB@fa-?BjGe8&H2Ipq!0#h*Cp&Mt@6?S{0^G>pRp^J8#8mB~tJl_Wa){ZL4Ln=)L zqR0(zDhQ%YR1_DXW7&ORgIZn7Lz>j2QY>X;H`sDbwbljG6@T@3T_6ZD1g-{%7_!rC za@#UjzU#^S>j{JfGQFtZM-!S4Y%U#SIT;BZ4n5S@41J zXAwlqDKrW->$|IyraRznydO7?j>Vu;d0QJHW+FQfu%||xvByvzoPFvTelfCoBy zhkZ^zYlgZDaOg+}b`aP;je&DQZlO=RMfG(8Ma@>FxQ;U;dK4 z;SFzSxv?a>%zn4?wa1tc%D9mL+@t_E{YBe##VK!Nt8V+T=$jR%zOCgopdC;;c^EsX zN1xkXnOw)9_hdZS$D?M!p>zinP#V+zd0`t<>JXUNNGtUg&PQ|7Wl7+&#wj?=D)c26{r3q*Q4)ZjrxPx_{0Nv0wiBo)PwZxxj9_^Lq2$>N~Dy zf3foX&g5(dP}jb^zxUXZQEGd&?NT{O2VxS+4yC;Uar?e?(`-6?)+=Yvmv>C_pvrDyD(@dMfMh2OIOyz4dQ>o=UTeX3@fc&Wl{?0bWA z_QE@5LQO2DEj@>1b}Nph4=>$Me7^KsF9mr@ff76xEiYw4Hi(5ho2RssrYGpOJf)E6 zQ_$ed@zSKcw(jZB!%6l9W#+53qFy zqah`pMU81+5|}PsST^MMI<`GV7{PS?Pp@I8i|-iw=m+lzmg!ShohE+k>;44C2tzks zo$kbiT%{jPA<=*9`t&ZOW7l7QJv--|bJ(g?tJuWE z#FUI(s+q=izw}}Go<<#z&{l49WkT4qp}7e5@BREB_PeM3mY7X|dEaweq&b6r-=U}6 z&bHlgYT|S1`@Xe9*k7Y&X;GgXZ}*HHz=|cgaKCZoOX9uVuRNEHJn>`k9XcnCKYN4u zyyuA@iQgkn%IoN9udjz@m(K-pO!Y;kNA+A4qV&=IUJ-oy!%OxvpFeZ{0rf4wDK~^D zq1uHsf2Q)2Cg)fER8aa0K?$Wa>ru7nM0^sIP{o3xjM7@zqO>UmO9_R~M^Vub*kjTG zLq7lYGsJIwE#g&?Uy($k;)aeY67R9^R$Bjvgg|A|qzdQgpDmsQAnl~d=$!)Vcn6ra z3@EK9-G1j!$f*m@9wa=W1ga|yKf{0bNvhj z4s}GQo4z_|N{QD{$O@ZKab#L>9LMx^EnIK<+MwWE#r!{c<*7m_>qP;hRNX{EcUrBh zZR<~c`BbLud^K>p?Bcsb9nOjW4Q>4N)GfTZ#}(8m7L-s!ql#*d(w~vB3*22+4A-1=N;0fU0i_9dsPkN|J>$qrI55rsT+=^+BN0Ry zflmPj>P(K@?Luj_xE&{rDB3!pwB=L1_M5zp?`@0>o^lW6qrdI9UE=q%FI3p!^EVpr z``NELkL~)+4-#gRr=R}L1RWHD!T}vt6D;-6x{aer4C5VFAuy#hNhiQAHa1~j`YYBO zsIkj~8uFlii=s41fFkv1TKspOV*^2Z&kZx0B#@`nr;v^Fr*tFha+NkAKTbCoVL--N zvlk^Eo=KXglxOjjvQ(~9p4#hNIu{sE5uP%OIUxq`ESjCvOl$$+@lUX$0jM0DAQP5E z-ST}}f_xs_SaB+0iIc45UbZs^s8~0oqdvJlZ*qIgjLpV$(e88RZYVm^$)=X%DQ)^r zqk$1qEI{3vgiPmOaY)(ue)r=)3_iQ-i5~{-FU66)$5WSZ9I8>Y{#kp3*0w~PijIRl zsrO%|>@jIV`lC>iT2i+RczljOAHQO`u;oN;=1{=iG|d4@^N?ySsqet`@xNYUK5H$k ze!b9=#_vwFPm`s_lxc7v`A2Xh)yTHv2 zrnIqVr z8l_?~V+7byQ950rZEFbg<5R2dudtv0??vp+|5(p%`TBb2`cJ;H)_~BY&F5l~!zZph z#T=iz*Ow&PR02}@owg-K8&N-R1hx7*{3QUd%KsBzI)#1o19zC`H6YgYK|5Bwh93A+ zMF|ByaAL{{hoq2=Dc&6-f(JrNW5);~2!rJ6=jW3~;_sI$8}9+3pn>EvYUphUWtFC; z0r$QH+623x{i<*S54 zxh-&@MERHm7*LXegly(jiC&E@6fOO!q5w zCSn3~MhY0pBX@CKc8_o#*wXz*7>~cd_P!IvcZbc}P^XhldRrN= z>^WPB9e<&axVL6s^7NzqCUj@hgqXikK+k#kd_e%Hf?9+wU$;l`BXYBt;)1v}QsX6( z3nc=jdIZ>3v~}Z=c~(cF`C|M&ZNn@bz-0cLM#shXMYWMI2GCPJnHj6sE)=6ZWu>Fy z;y=0OhiqPViS(OSpJI|SszV7i^OL27a{CmDE+418mgM6^^89^+wDVn<39d4&eRL1m z_xdKuO>Byp4rJTj(P_o&%Q=P-G%PFnx{HBt3x@74d}O4Eh{vi5yi|grKx-v)M4tgn zCD1F2P@R6d^?_0L{~a$Kn%3^_6(IVE1)Cg=qR>DQ``L5O`d@6-&#wu#kUXY$8*LyE z_dZ0Rugl2;+DyD(+pG#_u6h9JG?}|XQ>-*JsNKadgHp>24)<#a%xgk#!%9%7Z7Oce z9~A3=csFMWCI$Z)QMO{qZm_h*a4L!9)6@wKBpJ<#H#iJBM{KPMUg~|rf*v{d1W#$B zRFk}kg@>TeUtK`9mF*m-BS?cOvvr@@sSQCXpR!!{Dh+PV-IdgY*5=v7qkJT!_iL~U zf$0geg3q8PmV%hsWnkC;^uJhdH?R-^77x5LKOpTknnI@x=m4eSL+kr^D1u3v!@19g zHIv68ZF0l7!0Q}8Jm)u%uLgW_RW@GBKxbHeQe0@=af8?;cY>CqG$%i0h9)G$Q`%W@ zr+2Em|7&Q$u3RrEp^V+8;VCUjn^M73D!D}0Y#3pTN~je1bN2g}8q)%o*~FjZjCk(* zb1Xz1!p&y1Iq1E$9iyh?eTJdI_8*516;#WDQinIuKf-5u4mo(>bC_Y2XDp-x^Sgu~ zvW^w?Yg^Czx9xQ;=-JLVnv#mM!A%vmXkK?hu=NWb(^2m|Txe=>a%vEXV3cxF>gK_) zqnPkF0#pwjIr$1LA9qU~0;G6tu>hKW4Y6F32NhI5_v@qmBri%pSc9zt&+be5?3>?p zGMiT}vH1)Bq~S68fs2-~E#r|rA`j3X8QLR7YZM-poTai!L3nZEiE+%mIYaMEI{k&( z6myK2COm^g+i{O~%;v4Bap=Z@ljA4uQb(zKfeb0P#du&NLgy-Yr1_0&%Gz0bG*e0Q zr$*bwEG3hsX;L&#DE~oIKB8^bce8JQWUOv!V)>VqObc!O+tjYK!&90AlBV8M4^8PL(__z!*oD>z zBq@|oTWJO@*Zg<#&);k>ux?{QzztRza_kwca2x0=OJGXUo(dNr6TvKxGFmQBZw!$- zUbSS>J>6Wr*YdXRcjS5U=8gYlo?E%{kAxEn9vSx@`F6JZi61%n4k_Kf;=Q%FL~RCzqQL$Fx9u z^~OntrR9kdiIA}>zC5U7Va+8F1IDB~5OXd8%ei&lBxns=xa2mA4t~sFSN8x(83TYLLoPl_Z?`Ck!kp z{nYb56G3eTg7k~ibqG((xdn91>@bzicu+c(YVPn6Jk*?@P&*S=|1`Jh$sGlwx#AJg zZh>-)QQnu++yk-^TY3DfM06hEPAG(tZlUOYBL(SwUgQ_Ax|kNN+`|fkpQM(%}(?ulv(#Y6ggw-hJRj@`kr$?aEdb+ zA;?DzE)Rw#@#O*P!T9^F5jUmZQrR7K&Dr2<2w3PynVAAT=c z392mxF7v+cbGPr1p=0BAIrOPv$1>vof9FZ@_1`LSCEM-!o`M_&nh~KRU}iojtp}{q z@1RaZnQk|3g-}v3)Oxxx0HZZ_$t=O47D>^Mc`(EUraDeK-LS2AeUH$l?irKMAn5EZ zLy-JucZJ*6s~c7vKPw@Zd4Mxhng$dSWtL$^Nfo)&^P&wYtqE#K!5qaCT2AImXP#(_ zA>rX)vP9NFJqKyurtXC-pD3j8;~Kh{)Ube>3zTQ>ux#Ft7*kvcUz{f=6nC;Q^jT8b z%^BIo9_l$HRSPm5MJWPOx7!IHaQxpDF^Krkz^snsZ#Ru6N%d<7!xwOqQ|c-ju291z zs*YO)muQh2Wx>fu7tLJ4xrdwXyK~t4W4iWBcgW3}4nkshF2S@DC=d#2Qyp)s)x0f8 z0SXq7%6|nV2h{Pf;TZ&Tj}cSqZ*!USO_;7~hG{M*E6TZAK|E3X@87wXvBPCx55c>?o;0uNBBBD2>UsJIOHilFfZ&qKj=ku3VH4)F=@E%@km-~ z0-C#ls7G+5)zd{)lPh6f&Hq5}ZdMsn-uKny6F3%Le3UnZYqia(%oX zDXJ{ZW^m<@JOzlVmbF0AvK54Bf?foqhA2{m3V;4%HuCzFOS# z)32s*mJ>sak{KxqbenSMzNEOP{|&5NRV zL1d8;8G@2Y?_`xtY2*{ss~Yk2xC8bE4zSi3WJm2~5o+&TEi{~91tS|tra^nyfbmo8bhKfCzf z?r*41dwY8)vkjWE=LYx8W+!#;5;mCCl<_gI+|?5EK8sDDp7gN~-O0ZC*;md?+1J9( zN)459Qu|V#`xVGp-9N9Z?(uf+hfZbJUU9qk%Jgw-PmFjIrAdvP;y?P{^l~=*v*&00 zcx~jl?ML)w15@65bFBkPS>yJkSzt#x+x%Ct~c2&u%0&O6ZTf5Y{tW%+=Bp@*Tb_JKYRIKK9;*5=(ivG z*X^vQT%6ir0F4bv+}nKn&eu8LVc5ZA!xsV5JdEATp+CFjh6nI;jMIhN!Gp{MT?Y;^de=8CW>y<{8iB5BCp zxbh|T#?xQQHJA@sew+B2Zt!B>*fw_b=nJfG>_s-WvfWZpk@_c@8RX~J?S7UWwdZ+u zbmfIyBeer8XBJqeRAk(f>pW`_@XfoqrglnWx$y18<^4hy(R)Bf;d8Pjd1@`GJi6z# zmoje4=1LgOER!5hmkXTGQ+c(Z6m>lG&NkbCQR=&AE8k^1Uw16q760sb?Lzj&HM?A? zL4?n#%g!dG3bo~IyYQH{knar_rDMWQ^tPs>yyNHublUwxJ8B$CA-W(d##HB zsR=Wx${cYQKmY@0qNfRsb(@o5+j6Da{t{&T#{0ftz3&AjloaxpJ}P&+0%aPi-1gW(P8~?cxPxMtNF&u2cN`cTfARY+1vf zC^s^fEI)u98iUVmcb?_|QcN$1@6Mi9v)mt^M~}R~9@+1ATrjHX9l^H6ys_sP9W4lG zwZj+Xf$XH2nZ%}C*p$lXWZFCm?T3XYxiZs1^PM6R;H!|jQMD-TN|jarYNHb7b+)=`GyA2;YH;R za5jKcIZm4BX2RY&mP;610zyJahSW{M1!d|~(&1U<_2FsK&wK0W{*qG;tg$_I(}VYp zvggYMcH5oTJM@j6)W)DRxC{0i*Snv71^eaGlYhk@-#(cM^0K<07(4tqLb5FDg+kYH zWFnw!XgJ-AX-LJN*F30P*|TbaC@f726NZjz_ef;yO;;RWW}lCDiG{)}Hqg6AgeR5G zBVho!^7MBKVZZC~A56L{L-j~3OaYDS(B`pyIs_+^2ZDUA9C|Qym6GFaJYICsHWwGd zZ~~PG^c5EFCW*|X1kPA zJjs%Y;Ynw816$Nrs{LNZ2#pgnlpG;JEP?I)t@rGbb*!YHcN?8tu z743YM1*YlJ(Or_fgLwbq1wED{mDzp)!g)BO&BHXMO$Mo(e;o*ktN$cwN{dd%bkrL& zQV$U?_?KO=oX8h&`kf3PZytCu3zEPI6h#|ODKrbZXG>(M*MNFjQ{!*2w)|k1AGA3Y zTHK=azL(4Zk_!|uOHp%$Dzm7y8%7<PbEr*Qo#n=N=76f#3_IhYC@d0^Ot-u2iNp3{RUN@e{*w|QRxh}eJ3E9Nhd;b1gJJ{y22{x}R zMet|-)E=W=`fX{myty(VXt)y3e%tltrO)DRNDhz0?tR_Ggx#}#R=m5rWS>>p`^574 zc_3vQ9*tK0GBf%A_cuGr=31=)L7s=~PP{tLEP3c(NCQBD2Phik_ z36Jub6Ko|MiWE1;C(kWrtyr0tdv*{cF&2%4kqF9}0*|MN1AbUX>oJAwb=Gc_tgm0agPpVDRWoWiKsEtQc3$h=%G1{g4K)5n0D9u7KW3Dv z2fr_V=_^ z`BJwqF&G^0V&}BT+E9z96ai>Dc)i|4bo$sAua$AHRlIOWIsh8NsN`fs4th3xDrFFC6K2IrKJKV9txpypX z29)i0LoK&y+<7NHD+$pk76hvScnglc zF7jeL<4~CsmI5B?N)H~{d(i4Z(s)@8yqlgavezE&*3RL&_E%|8?{A{8+`EefPsjxz zF{hI}rQ~l&_C5L1^>_;q0dq4OcqT-vDd+fPYA+u~J5Ap%wBEdd1<=|Ql{@=coNG}w z= zUp&=HlPl@SBjdkMJ|UIT!2F&>{#pyG-!Z#fF!rKodulYLq!4c??PlZSkyv()<-5g9 z-B?Hx)ZcplC_DWG%eCp-Q2BPDU;y}dLK9nG8`@(q$Z50NtF!)!pCl@ghxpH zA1_wdtg#_OPryh`oD+(yTJKJA-1+(o4k5#r-*t$&_KRQqVy}$m^H0jzU%*`|vYhQ# z|J+IgpHN>n&(H;S`emC%>j(L|%nO+bHRpVI-k@XYfY`WO>NS*4>xakdY!JvEwIENv zs7)(=IY5*I=>%z=)M8Vq14=t-W&&>qIHs=9t}qPQ;|(eMR717G!6oJoXbHRF8Ei0vjDu~}wd#xy=cx1G+Xj6)Rpjm``K4L45lX>4= z+244bV>F<%6I5X&Dpa`sZ45LzQFF}q_?!a;mcR8 zt$X8k(S?hHV*Ao>1#yE&Pj8pDblYYXgbg0HYfm?i#~M=+d?rjFh@LLA#jOgB#GZ<@ z(?c6)P4R=*ckQVfjRp1zUPr1k5#dYy$ml@vH5L5_azb86L&}WwL&J;RR0850c|(JF z!DQY+&ikblzs;tIB4aSb@s=vfweLR8TOF3$e%ZU4po z;`H-#J>SY&)HVdA={wDKtG%E;0!jH~qJ2_ID8-5CQbNgao7A>bfR$IBC!XE;_2TDIom{cYp^n2(0?$9_Mk?02B%ZQ!8`4?je>z z&vw?;R5l(gA(Pr4BkvVmctSO}8jz+cM#+77OE)OA))JUv?0R#08HJl3Hv~KwHZxqa zO{3$Yy^Ar>UaYj^UtGIKI$0?X_X3)0#K7(0NS50;Y1NtD`o1O7nFxVjRocD^FkU2K zA1N?o(qy7^V3F+^bH}>i!Sy&K(dHQ)!88Dw9XH$PxLb2;_iWn*H%AHF1s)cgw4)R3 zB}uTaa)!pAhI(WiWJ4)niA_1MtW5!gCaC2LhOD_c&Q2CQq|9L(xyNxxVu@1wWz#Z5 zjCFLZ+cM$G38gVL{Lrdwcq+6O9j#1&jA_dGwvWK&luxz3cnuu>BX5j?v#}nnjIvH@ z5m1_CPa3$pWr67440+h^g(zLM>N}$S7tPg7kjndBIU~_#uU3=&w02J~TRdw|4CI&q zBZxy*4WG=8Sh!h6q}t?q_9I}}ueWGkC3#4#Q;s3fPXN-ciNb;~l|ge<2{fI8f( zOmdp0(Xc^{I@Y2DPF`0wqC7|YX&d8Qo5nE#OdT8l`Q3`gG`sAm?L?}pstBEzj812Q zV;EV6_N*mo7n{i04p7bST5lguHTG*cEg%7;*rtcZ>(_JT+A_Eu?MhoxQ=0AU6h4sc z*ml&v2+9zp6VBHnWS$57gk2NStRgT#P>CAYTko&1(~noqQUxX=L*4Yi$>Q%v_~Y!z zl-DDG&>BgpA&nB9DT(_FPC1feBdICXgyxR4Ae^c57yL=45dG>`znZ%l&pPIRrRKG9 z!+#opEI$+z%gX~PqgdJugNhavIr<|6uWx$8th#_GCxo4|4nJ2=CLOisc`0uR531E{ zO9wKk$*igc9u%>ESg(Z}9ia(T_2pu7QdLx0T$wc#O?&WwrnIPz-!V~5s<5*q*M)Oh zRhd4ZSp+KxK&%0`dtD#jldzA95=vj!nk#(->qpR2Wo!EbZc1icC(7em>CV(He+DJVfZK%)4ahS}d-6b1e8cJEqr8MVS znsedMGg7CCpcx{zXi^l-$CDT}C=s+$<=alMPgltlw#G1if4 zOI;TmJ4II|uD78Z`4{ed$+lbEM+ZIdCFlAJNAwvPqT6j7u3z3-v~K;+*!#|USKC92 z0_&tss*#T4yV!#2OKf4ZGjYvz7UD|qjweKF9#Z->J7=-AyL;Fx=Kh+!qVGYrWWg>8 zK#x2x0mi_~*Y{iS%?r||veY!8~LcP)C1Jb>%d~1a?<29xAcTBqzg7F$x z-Rp~bM%eg-kb~>UH{SyCPJl_S31AXOSs7~~zUlHIb)%mc^-!Xa6 zs8Ndz?UPHnSvIepTho8%5z6s3+z zju3S>PttTbM{RtnXX?Joed@~vlX^L)lxK#b$?6L&rzcO2f1Vtlp>3WXw~i-$fcusk zYBx^ihcvTUa!k>hk*K-3Ruk-Vm%<9ukuUy+jn|+pX58f!<{q0FwQb_wB@Z~LsMJacFs^5ihvcKFc-uW+971n-cQVrp4UX?=F4?K77$dD;V4@q`AC z+e^fr?l`t5aqB>U@6!NP^1a^m%j0)Dr4dNtk0zZ)O{a`e?dG{>w3@1k;u^#<`o69N zC~+#ySq+ggJrjav{OQ*O{IrcKk#O$8ALG>4S9Z14+$G5mZcKQ1)F_8$ag3Kbz(V|| z4h-NmwKzO2fB~m{N0-DTy5&3s(RretJ^*l=hKCB!urPr%Z51?6C~-E0T%t8Mws~sL z!r+rnR=y?24p02=1I*Af+>+&UcRp|reD)K@4^GH`d6MF(n3$8?5b!%>nSMKQ76k3wMfOdXoHNgcl5pGBgHO1-2JsGqerto$5J1f< zDqA_#TTe-&qkdGFpr1Yk!3_K7l@o6p+?=$P8VK-+B9Kae*L1a2g&9HLL?uxS#GBKZv23-8E~EV&5B_V}9~v zW_^Dfb5Zx16>L5b20Re%_i+6oWuQQPvk00r7hwwLIZP&#Ox}roN<07wkNa8~Q<@|Q zk2CL-7Cd$gVb`wBm>^}$LAVUo%m~~~Ut$;od-mn8WrI(i#@0P?YO>bg5?nd2OZg2> z{eh*=l(go9wpu&WWxoB~ee`8)_JU74_o7W{^7+8{Vpfyd0i|t_uDtduwT07^58i2v zQXwpm5PTpQEyX`KK6oO#W#jL%S06qr++6W@N4-2s&)4-ajsw8WN#E)A!jP*!aO4n@)G2S%OMNRLZ^6c7e1xdM}0e+7p)-<_~* zn;q}A8!UHY>il5A{$${R1aF)|t!_&I4G7XW>9zpEOBn(wgbY%#06}(Lpq|M$6%q-i z?A=Ky0#hK6@?C}?C5f3A!i!Tc?MgN1&Os z3lmOS83IyxrlY51p>_9U7~>ut z&d{?Qsgck&Y>4ofCMOH4?|UY>P_?JCCO_yo{9HEn?DdH(dJa36jXr&yxu>E&@2h!{ zw6}%kC>{ZNOB`8CHqBp3mnFU~Pq zrNSX+#{Ww>ym;}sY-s5Ens1*YbONf@C=0s^foGH>A_nW|Dtf?EGm|iB=OsP>8=j%y zveEQ6%lA)y*?&^-luxGz?;d5h-+2S8RwtSiS*`<0XEKycy|QLwMMM>9#e{&g9$+pU ziHM`p(8z3dIqGO)m zy__2H+<0~gWXThz!Mx7$aAL+RBP=DkLk%&$Z@L}gHm$*Ji}My~m)4k?;s7CQ( zb3n!dc9Z!3(O3pPcKi3l*YmpVuzJWN$~R%~nvezsQ9L9-W!k1$QdNNm+{)7EpGLCU zmjD79v$NzW;~MLS9=+x&*buGFg*{$BZyIMc)lidGprvPA>-d?2-*$P%TSWo-0E0k$ zzqB{NwAjS#a|ApY?o((&0n%dIlQU*u+_Md3;T3|Kd2nJD;F+l~Y676=UM!F96`@2u z3<`lp0{`efU506{&|)bvo2cx@vv#j*HjGZq0EK-g|7L=WPVW{Qde+_av@Z^68&G=t zoj)-$BafHcbI(0DBkS4K)inu4MEEL=q#^<8a-s3->n={R+&dh~w3>q@uz%rs#tTmy zG(4#(4P+uHqqdCKIb-XX^BML9xQSZ4z~v-HSs+isI?9(R1;EfiheD@MS`w7jv@@+S z9rd*{-qFQw{{DEYwNB*74eNRV@lM zT&8}ke}0$HbW*N79gbRR1}ome0uBQ}E6{Q90M{Up!=XieWnoiF+Y#9bGHpp~#QLOM zjQHuXr(;06yDWlVY3^9;o2XhelDa6uh!&hkF|zM;)TE*^*#L9&F0ONXe22=>X>8m<|-YvT<&?C>8CP45#bM9yL}207!!L!49QXbJYLx}IvxbX;$(#9 z+f2}U8F>+3+FY3kKKpPa8)mWd9y+`FX=$_wt1 ze+bhz@nVReFRao@ z0Y*Hp(tta_*yUBJHTIHB>6~R34aeEt+D1@~s}L~N>8=MWOq=y-Z7Gd2K0F@f8g&R- z7tZQV0zYy+2n==J5ZWYi0*K2V@UxF@2;{w$Ou-E!mGp9tra#L`n;|Er509%%jA*T1QnH?alzOy>u{NR6C}fBDjCD7!J!iB zZ%(wOwKZeB=Jw8)QTIGlbwCYIdkTEjsXM+AnCh}~GM@i-c^-vBPJ7Z$nzZ-^p1wh> z7auh8Ob3)s%RP(>PcFNB8N2M_yJlpa&bXkzz9VwTi(KnZIu1H&Cv-%oB>7bRFBbKK z^lY@3y({d?Zha?-NT!ozek?f#h%?GO&_ebvfH^6 z`$k8r3FiZ;?}aS8K>9~4#X&@r0hT(Ps4;Eg2HR-hQMM$9hSaX#O*Blxkqfo7N{efq zv@piC)V%4md2B+0BZX9{9WVm4&#&2KGc zKP(C-Gruu6#=!D(ckX1Ru95(54&4!#;IJqh#7ag}Nz-TVcuCZ|q<|f5V|F<;0 z7M(YQdBy^=DwaEIsBJe%Xn(DPd;kfcguwBhtyPcI%&nm_q#-oU6=fcl{peDlp82L_ zol3x#)p$0ujNpvaWVq#-3@kgKG_XtXKW95eq?6z6zWXf=PC|Lp7uN1#>xU@**ZR5&Nzcd}ydtQ1z@xwL;7`{67`{tanOgu2hPg2kt z?Iomu4M)oZ!E$3hl-o_`ujep21X#)^nS%t!+!N>;9>9z~!VmYE@5w=lvI7j?0j@?0 z-cTF*?CzczV00x2w}Gtklp_`t&mt{jjZJOUF9?C{N1;$4r4 zdfzkeI`zI6$M;IB#?gb{u-+uS?_JOi!VY=8*z5!d&MC(#qyg?QU||7B#p&*X{(NPmB z!*LR_c)BS|cq)OnIiUry*PUkJF8`#a>qNP7^3g??T|PL%E*_ZGo{FgHU{9*JVkaMQq6122Fi6b_ zI+}@1_>@18E5{J9JE=U%#>Zt``-Rn=>_OPi06t6~UbbJu@6>=A1)mT0#PPWZQ&}+f zff}eglu)RBQj=EN_Nn829;zKPc3CKVrPjxNXT(G2x`B|EGa%{X*q0yOU1R*X;W5QA z^pWdi5#qDBs64Urmo27*z#v`ajH zU*K^($^g{D7M0T?Pc!MzpwZZocdOtYMX5D2FlAF(Eebg!HQFV0 ze9sIZMjL3Mr4pMUd7Va!6ONi@OxTL^v_4S32l`N3x`&17*ti&LR1-@zrh}U*$)4ot z-EP|48=K8!KWTYzxi?TMPmv)VP}+JL(mZL!apjq%3Tt9ox_^bmSV9=TkB>`%idxfO zv)TKy2WwvCJiO3mfpGyyqo`>OdjI|R@0Hd#|D@XYp!3qnbGum67({sT4;>1Tdp;~n zkLh8&%GugY(iv&M3p0z)?R%&{`55pBLKe^OaYhx6sjB8s)lOKYqB-?IVB>3XizVrB zBd<#*EIKZSHYGPxj1^}1uA$tU--`nzUOY57G&xM7|4nuC?H>G%h;YY!^go!nGa#MsV z>nLyN%@{gVgFO5hpGdaLH}5&S;oa$yKQt*xuAF1m0@>b1ZBR-U0F?Zx{0N~&G5&VrKdm2K+j^#|xS zEvtITUKIc%3h&eg%*=Hq!duJ-&Bm zO(=AFV2lN=N+8gbkS%&iB_Nk*hhRZ`xoquSec27pI5l>m80s_bvt`HjCaVblkG=N* zkhH4u#m}j#4%5RhLr}?i5;;xi31kID6tlZ3?%ThQ_34VMuDjy8`&?HSS638#g5n0n zu<9BJDhvX{3=?{QRY7EWB5BAlc{*3!f1R7}{q7g4x~jXYtF8{+{e}D8e1G?Z-|?`f z7t+@505zA^_6}KNZODqerc4vWL1>j_wh(IKY&#rg-#o^5_i7GEQs+o;El@g6Cy8v& zv9TO!<1xB3rxm-};hgD1!16+U|I0s|$*)rw(b~(ZSeAz%lcY3J0$>*Qks>RDi1rNq z9`%YPrxR^jU;!9qV!&AeFlU$pWKbl z05^VL+GWCM=|otXl+g9CUg%M2g|fKk;X&B1GoRY`v>_|nr9`1!J*Gj735eiv9F7I1 zi!^yYi;=ovY_no)8xI-#XBL$xYJnNlNPQnWOEEQ1mNa!SW*)OlQ?SBr7B3yK^BMm0 zg;yO@;v6KQ<`>nc`v8BFmTu@ruQ81eOm42lX1y7w6b6&PN6cW>){{D3S_w0*L zhP_Yq*0IG|W?&dBcll@6;ctb$Z9jMN>pJ3Xu|8Q)2I;)J zeFH2)38O7A9cCcrksx6T@;4iH{}6*I?dJK}LoYkh_1=QZ!MSgs1YI5RCkyh}(Sw9#odJh4DazQfjl(Og=;5+lFgOui~ zM8o~MP}xB1qtvNNdr+O`~`(QUNE-Bc5f-S<4G5%ijup5VaLDG@`rJv^RK<>_uS0zhQ=Gp#yh z%xW2CxOmm?x~rI5d!4tkhu3Y*xUFb6fm+T_+ExapMctYLn3}M;s%1DKKR-Ch{zeS1 zBFyv$vkIp2p-X@H&6jEbDzm-w+u!~c&OGzXCXjq)Y#U~HXT^|cF_lg#P#ThqPJ~ch zSSjeNMUgY+ao^5%4vvmIX`=uVPj8s;X9WdF?Y8aP_Or-y#bOz(J@a$DAfWHa)QuPB?mc{P$C;F>CNe81$Nt zfa$Xb9a(jmuKv*76~FVQtIl!TJ#kv6FAQ7~y1w7)^Pw_m?TGX)Nmd`SOii$=HHpEC zlBc#L84t86OkOyUmpILr8qbocLTEk4E>!bGv9Y}33+-_7;ui&jh@>!c z)&U-{L9GMjc5BPSOPv^yLtrY#X$HH}h61Id1)1YZl8)I*Qj0=bc_f;)VZaUw4B`Bn zPpiHN$~&CG3ND<}ky16Uz|3p01bZ?6*1h-qh(EvNL|05l4z~FcdD9BjJ_l06J7Gin zjFk2cd>k`uo|*YM(Q+qek)0WX1le-(mI2tl0oMldlvloA28^y1@9c6td-KyFz`__V zH=1!k;C^7p{cuj2HRO;%DQ*}`Db!FAVM>lUz{c%8-$cL=eWgaW*LKM0 zrkg4TJC~jEKJ$*Zo7#5uD!sgwOnk&)V8hU`XCsU9(AMGb2~)o;m|d{wr_A9_@tCrN zr4qe1_ANyX?G;9s0lLn-nTe*n%D%Sg6K^MJUgaz;QGPhI)*f;=D{{)ZmiB(qNlL4R zrC9%OW`v_g3eYynNJ=bwYt-M!8mr;}MJ~0TsEv!@_?}Hrgasa<}dy5;*{*8BL?HJuB>M+CnR^p5=%UZ^bICUHOSe*wsW(c zM1)Bz!jIP+$FIGsdyCGus}n&5`$0!S+7T(c?U)uu#|%PP5VOqlfb(3~LCE%g9(I5; z{qETCS?~{IHvd?j(%5pF_k8Ik$};7p{c>VXHpgb9l4c!RG^fMm0hNwcivKmq7Y-f9 zXN=KSV$?+j-OhV%UniUpbl8c%W@oXb>kxQk)vNR~Z#?yphS-5r*k%z979$5mv}~J2 zL?^>zN`1yDqnP1@*$f`04CB{1y zVpL|)0;5d`N)vfX6HM!B^mXTVmgdkiiVqWUejTuD4O$?hGmbQSI;*`OhKEbsUX0Yj zl-B3>Ps!cxPZp`9u%89^#iNF2skd!LAb4N;*oePZd5iw)8^X~EBCLg;%Zy(o23jR# z-xq*U0Mj3=5`gjDi?-^AxD=e_QX(d~nHnjKDAhy5GvJ}+?qOjA9Uel{i@6d~-90EJ zq~1FtBPD2W&qdmkexry~sowW0x(|~oM^gQVyzk2eTfKh3^U@K&E6J2CG3B2BoLpa; z4p_wgSt+3$K24hvO2%l&-((eh$C-f6L z_`$AFDCz(pMOKui5h8wXUQ%%>RXwY)$(lihKj}be&Fn~7y;hywx7Y@ zEENt=uesoUc;Viqk%qEqvi!y2&8Gw0c;k%~*Vj=2TB-N3?~6^F1EGK|Vfp$a!*1Qz z_DzNP9ed&C702jPI=3k;u}H69cv@$oT_cyK4w(G!es~aGdxo&PoOj`FhgONYp!2ZH zVa3XyY9e$l34Z;%gh>U^{Wrt#3qqyYap>jc3jQeC_vOx~Z(evh(M;tfsALs$TE>qK zaKI*&f6a!0$gJq$MCOIqS%YIR?|U{3Cf*m$V$72A4rxFhSKr7t$^cwB0U{s;vw>4F#)bV8GIsT0Pw_hEC^%inTN z2vl;4ic7CKzYI{9FCFvI`p;KPkKMP)X7{=6<#8gNm57Gv!qbEu?L)&xih0%rJ3*Na z5@@;L!gs?Rcm1~jiHBbfeNRX0P0msS&)o{P>YV8famaB9vg6d>ci)f8W6?D|S-$)y z`gh8+P`=Mq_8Wf^1;B%>40_u&PpPesu9z{g0xCwO0`*gr$UNo)qvRwrib|+MzpKK7+SFGeno$K}P3Ybs2rKjbcER}ml7F@pa#3^| zvp|H@_mQt>XlnsTYY&jB234M|1O|*k=vp_iL8$S-*DK_bIhu#|{Nn`sXikt_Yxh42+|Fgf)8!bswfAjmkSV@gi*>SS~xv+BYe#D9bVzk?y`P}oLXe%tp>)Jm?4W3>6V)3YgJ6Acsr+nt9olk=uw&3VJ&%@Kx53>wi z(OL&A&d&^!exl-4rh_85ZR+#2GJbH9z|@*Q#G4yY<lBZH$H%z*_cAGJfnT-0lo zXstGN9O#X4BJ>x|QH4S-Qix&2;~Hc(LhjYR;Dmy6LlKk5vV37pmWY(6S(MfaJbqVF z@vl$j3{}tD-(R~S{T*iUquSA?qFe~ov_$+uQ!KIy8Z!_EwIN_=w3HzQdys|;6p!hE zH;yUHaGM8A+u*^?B}fZCI=kyh__Md2nn?PNnFqGGaLcVvPpWk_i@@NYu9#lY7`*cO z9S~LOw-P_!G*e~6)2u@4{tCVmF%ZY@SVSmBsZeN6AQn7GV+gVFvYKujul`l)j7>M*>E z=6Q75f8Stqv&>nPN!26|(D?v&gaX@+%^e52-WUb2XfckOq6Q|L zM+s%~lsa~Zvcb^GnFQXqKYU8;X&_=#iclk`sR^+ud0ev?v6)rA4c!*+vuaCjr|nUZ zEmG8G=#Qr4F*=qp?;9b!XuUR6wENH+%O>hrb4pE{ILv5mhF265hIucYvueh%MryM~ zGOqIddplvtegkr_iu<=cd^#L?^2Qj+R%d0a3LEd%9c2ML^*vS~p=tC)z;v%P`y^mU zbWr}Du{om_m!f8ui3YNNWpah+A z?&i)c|mPI?7l zI#5iZgksX>G;eH5L9!YYd9o3}3JM`T&&T$^&CTk5qta=FRZm?7 zNY&5FPW!_IUboT{k@RZ<{Wy-!FV@P5R-js)4(xoQc_vtSv6OX>1>R;E7s^pqO~tA&6p#bbP%^+H?we_x zfVDl9{?m2mCAvAKIzdH@>H`ljKPph7t673we&ehP*Ss$|sDO}KmiSMKL$83T-R7yg zJ#z;iM=YTfhsV3{)yn2=0%h1|3zp>8bBUjVCC19Oq*4Te-WF*Xij$&Vs{F>~&N;YaQu{wdo)EHVqK>PC&cM%r>VL-#WOg;?CLoqetZw$1w zP683f4OE+RniCgVWvhHOm@o@tEJ6gh;IvL2&4>W&Z+_oj!I;M=mBDqEc0PS@=jjhBmw^QvL8qCnLE54hWkxHw|2dX=RlzK-baSGqU)Zc#DO!9%`T$2FelnnQ3LB@$xud7!{l>C z8I3B(cc-Fc4q(#TU)>M4yR_Q4}5pVurwU1vWdjuyx<(g}V#jkh*JOWf3DXjulrHWHeZ@kAWspecsp;VjJyoIVP`-UM$ zy;#-PJhh+t_5R1Aq4gqCos^DYjc&-3(NyH3Q#-wJGnAfjtU8+|ew)SEM}!`C`pZ&3 z(x$qG#&-E{aV?yYvYr0hbM}uc>c{oHq#q?s2>Xu!c86A_yhloueyPpCr#%B4qy9;~wHY&`lyk~_ynD~O-qf`!0}6-_GRl2Xq{ zsl=mSM+as!+!V)X$5Aw<^g>=C+0;(0x!dS zszlC7)20?opRnlCO=Ztnp)^(BEnoMHBU#Owh?CO|Gs+^HI0iR__~D8PsFYQ6G59N! z2hg^NOK}B>?BZ8!DwaPI>n-gKO)Xwt?8nStvy0cg4XdrkpK3# zznyfrqW8AbM{x*oDe=B}=fA;+-f(48L;8jXrIpYpByCxnUI56~Rc>564{#1hBTKHx zpKQqDY``WSroyTyuTe??ayeVg*a0T2fd6i&?I)8;#MJMkm%j%?G>(hWr!G3R1MdC9 zkc_%iN@$+SdnIg$5fj*3npl*W3rI;#rPu?ecG^5iOaszFAzX9yD0%9u^o|9aG9Lm- zt**%T1vx$odf#InC4EuJ+}G;+yyS;PL)>3V_r9mZBRW~?dwNfK-@6f?WZ8J$GUTw; z_*|=EH9M*7+uKa&*KU4rD>-Y4m`B!Jn$sa{I#W75$*wk)Z3qR85puJLk_c)b+m)Lx z*k%(2YAb+qPM#8**F;R;`Q+ZnwX1J7&Rlal+h9|XWuD@gX3vZ^k10A159GWi%u$Mx z(ILm%_3Eu7aE-&USq&W&PRdm^6Cl0y^ieO}jZRD00;L&2YDK`XMl_$HFFSGA%W2hP z13bcv+Dd8BMYSnNkIQ&)9QPG>QMmt)1JdyX#U?2?LZ+hM$Ts5lEiOlO|Kh(`0JGZ* zFlX+2s&0>~KC%cljfhQU)gK3WotfO=<;VF(OJ!JkQb%&tSOqPQS>E^KO`A}Ljh?7G zsm*i9w8Wf<=X>+h!MESL=aB(8|K#?B)sjWqFvYVE6OJ0F4-oB6+mkehyzl#m%;rjt zNgQ;QOvEOP^5Y8v{Fwz;SsjQABjIV!^w0!`S-S zKSTHA@Xl;5jiEDCDBlRbD0A9;t#X8t$^xyjw+;gKP8gyJ>h>k1iDeJ9MSQyvAYRiu zm@rW-8&q9AalO3^*eTw7vAjm{fCq_vkvx1dd`g;!w4e1gw*;n~-H~64lZ;&gIQwRVpD@FDm$@zO6PgbHB!etRRT7 zSt+OMCc-|7Z?BbMF#V_`S(6IA7}WBm+NoL8IvFbd@WT&}*|<$o{lz5?NOQuw_J{W$ z%dfqA(bi~Vq**uE*I6~~iNWlIQGTTH>si}Xg%Y+?OK{B z#8!>Go00cv}UX$}Sa+%oz(4915qvA&YSh z$sn)0O2abBm6~s4reLSF0Xy}|H7v;#W7NJj|0$E8ceNG6-8au+Y3(dk(!|HfoUoZ9 z9}2syoW%HiC?9;=+B^w0d7+o@qjX-=66&7U!l(YvZz^hmjl)IwYEQp(juYIq#=~7m z$2GTYc|dL$8j(_HI9k*2GBt zvW9CtpR_Q zbk#=|Cwz8##wN0;m-?r|y!O5D{riv6*SJlo1a4iOIWE1YO*mO9#wzL*<_&R-0TlLt zUlVY)BA!!zPy+H$FK?XXe*$!(^u9+O+kU|b?NDUJp7<2HD<_dP$xY43Zfp10KZAOQ%yPd_RDqEy}c-uJ5PB}u%m0Cg^3EFW0KeFn^^ z|Cu;K<|Vnl;*K$@SkaamkTN47Rlv*#o0`*?8A!(?K&7=KW|>a$e8fr?MCDPyjoOvw zvS2lkz>YH)2&XJ@zX0ntjete8X+mpaWuB=l5_8r)9em;I7iiN64O%U;2`by_KMq(b z@VtesS$IvhV%39p!07fI{gMfr0nXijFBD73him&YJbyK2EWpfZq-3&93VcakrO31y z1bXjy`?2u%-`kZ9smEM?VP`4a?=AncRz#;PC%-Jue7t)~@WHFM?lM{;X)_t!LwMr)|~z%AX$k>O9KUSO(L>(9*d|1L)m}n{yp04K}oO)fG|gm zENl;r^hMbADL`6D+EQf3Hc-<4aQnn^{_p(mZr&c6hm;8ww&EdGJAhAX_1mHWvuB;Z z6WR~G9QvRB1#jOAE_^rNWQpsusuNU9n*AB9=&{6s9VV+vrm6`ZW6U?98+tG(diY1|$C<@d=l4Lu3 zVUKQi09q7Y355(yIn2<0^u5I=*(LW4XWQOo2+Y z_lc^0RON~>2}<}Grfu@;gpg=-n`rVOZWIGvtOq{3NlHsG!qfV;fL zwQ(u0pg=3KlH@s6hcF@KRTOAEx*0!c6(=>WI_V9EacOrUFQo5OR}J<{C2^1`w_9Ev zvcPLs6w>p-j+_|Va?RI7r7fF^$q7p1ou9(f(;o-jv)e5-^XRawYeZhfn8V5*`q$Na z^?sXEHl?av6!-yipNB=1&B7fhm;gVYT)H28_rdD>fQa3{vZjyQ%c2H$CQ6AgEyyQ^ zz)PzyX7RqrV3Uf7;w$IFvYQ^r{QRXKUL5NSWJ|Rc%xud(Fy!U4FWkld z;KcLK+@fzUU;Y!g=%PR2zjq#fIrKgK^DL&y6^zIDofR{9rub%cp<;F05o(xtia;pY zDEDxZ{#~b{5J_C1XuV_BtBeO@ zj9YP%4*zlN4+uTaULe}yuzU5@?T61a;g!?YySPJ-_d%?%rx8Q8tCJ6qhB_6UKJ`xn zXq~Gu@rdNhe43TEYtlbJ^`+&*^kiJk7SO|d@lO-xv*Q}iAp89y95TqdQ=?ZQDds6~pg zb5AqGie+SD@Ko+uII46Q2d5gCvcQy0UK05DAhQW&5@PIO^THlhnoZ;_a}{9=Y_FTv zcxQGoCf`1L${Ua1rW+KJSJ)vNJ7r~~%u0FQRs|&~#i*UJZLV_PABNny&SHb;wLod( zfz28NJ1>3Xn%>kLzESBH>tuX0I5-F&{fAR(lGme;P5@)|gl;}T@|1GZ39P(t>CUx1 z{jvBf)z+7dRmGVDP=#rM*ev$-yS9l_rzq2coQ^!?0<;pm?#wBpES6hw+gXVvv|Gg# z^~~MC36S{d?uQ2jH!YClT|{isAyo%SZDzho>Q#UHxh*jF7R#uPnr(CYzS{AC1z(sj1| zPSJkq8LRGT#nAUd$d(yFpuaZEx#SS(U}kKnZ3i^!Zz}tYwmmTS_=9x>v?5o519#Hm zegoEc7V|*@I~83GLk?yL4{a{#xu{GN=ADq|r6Z^2e7;SZfuXj~E?UlU|Ffke84f^} zs|X8xGnbgjz)~Cl)tEc~ln%J};Q?qFk~WE?)CR3zyX70;tZFp`tP?R^_qjhrfazzh zTF!s|<5$ngT(>X(ug5b#o5Y=$^(EVEB0c84NMt53>SG87{3S4hBC1|P!?&eONMs+m zx33gaFsx(Q;%;Lo@NUJWLC>a?M=ipr^v!3hB8Mg?jBvdi%)QScF6cpqy2;kycD!>tBP~QWpoYlZE^_?DjQ>4A?7o1l9L+UD-aWXY5W-(I8z0E1OXUXNooE--ka#VTrT+mmLMgkSohMHyR|d8xVm>9c8j5%yN*IA4Qo@W#29G)TC?!iF_ikd8C zg$WqMW_pKtj#U2hXdLmFWBr&6ONj><(+;Sz?QoKVtKgXvD|enlh#r1}CZ{b>I(ZWh z&j|pSV#@=m_ZusH^&cOBPyFNQ;$Hm!ACIAb{PlVM7@_JP3x7Ar~n*dCsbKqzFh9@kq57flwOnMT?e* z>?z5fRY=b)Y9blF7Nlh9@aaW3_Q?Gz?PkkHFU)Vk(rikZwl376It7R-IiWONRjQ)8 z5|mK|$$iUs-EuI0X1kDjDFDU6tWT@Nv>kADlu#nvFVQ;Llu%5uCO{RGP_k@3C6u8i zl2MPO!K1z}J$_ZW?OyQdhip5_Xl(S@4u%M~m*fszByC1Nv3RO^_B@+%NR$=1sy-k1 z0En?(zQ2B;=ykEM9sbGt_jg}Ax12wx=TYzHWN5yE2j-RcXAXKtiiQr$s>*TY!yI?~ zgj`_mi?UzyX9pz8cE7x8uea~GI&wV&Q~;F_iq=r5<(Jt5gkq1eKL^tvPONc?yr$1CxTfZ&rNa`(EIA!*4$v; zn&smSzdwE3QPb`gnHOsT)25P?X2Ca2YuUjX;WN$GJ4vPqS4*BeyH&b6M07A(Y?VZm z0wR=H&T(`~OV96ZgXhUcFGQxE>Npl-r-o51lVr%Ni1vxn$zJ1aK<$^S<(TNWwWsy!;u?LW5^)H|HC5E&GzIHWj1tFp70&8W_>^S_Rigb80*(uu|H%A zrid1RW%1+QpBHgqGDF|F+Txdt>ldFfB~4Iir%x`~55Bl!SEO<6(9kRb`~!U$0{{P@+en4~VGIJV~igm~ULveP^65Mdv>wpWT)f->*PUK0d;D}1yVzkA!3L=;2_4VBB>r|S?6D6!nj5x z)}K_MG|u^H#r?m`G^J}7oxZ_Rohq(WY8b>J7^Fk8nG4;EaVo7ERlPwwpG(GK3B)nI zUXHO7IQD`(;?c}Nu=#{2_a@w7z-CbKswQanZC*+tg+$G1Nory{YLV$c-z)%y!%eBA ziym`fu`GADvX zl(app;R0ov3$!Gid4#l4goth{l(c%dXy2ETeRbcLHiC2(;?8v*pQbZ@5H%3BK_z;m z!@;n+v6e0fwh~(fZ=mn5S>LDgRsUlcH@c&NX4N|jXSX}=bEhS#WzZ%bvh3?N4(UEZ z>3m0H+Yl;a?0h%t8b$!1TAQ73+hff#HBs$=(7aSoO(-d?0(DG6QF^WINo&*gDe>zY z5s}whih9L#_-fApSGx;Uu_E?IE`>l9x>l-?o%<>jr<7onq^I*e4-b|%!V*lInscOI zE-=N>O(66kQ*^TmIe;kEfiNI-b0L+#{m5FSvbU}+kd#R!%gdXjs00KQMUGOj8}IwP z2^pz8f-UcR@)pLN0L|3y+@Yoz<9%Pgzj}RtOmkuQ43L44-v$u6ZmC@tXCIqBZRmRs z*wL00XuM+jsK+>uGQ~|Y3h=<@VvXl~G;J**9G|P*T3`biIwY-KKbYK^m{MGf&YzlW zW+59|s}CwU*xMZNSW(H01fC9`l!iu%(9xdL_Og+qB1SN-Hu;GwfPZ;iAgbJgG$%I9 z94bnHtWnimxa;XxVl&Hdplk)w%#=Qp~mrv({wmDiYyKe>%QD;Z{fLZpcW)C3hH*Ry5U&=BAv8~TwSc%!#5e|kzrZ|uOm5W2`*Pk z^Jhk59d~mH*Kp>M+N`S`X#rOMalk!nL_MJbkOs%J9%LTDowmGBzvjg!oac5PF}te# z4}N}&^Y@O!XH{4)mU<`Ycxdd){q={1O?e|w(+~ELt>CPZgHQ{UPEwdP3Se3{8p;VP zhBv^579`q)RG3iiK}egKJSx&P?pZ18qVC&VZ24TiW<{!2$)48M4Q)q^X%Rq@nJ7Dpmugj-e))}6aMec^m){pl|EJEK z9<0yHTZRK|!eA@&>6^xGE@6#x!ZBY6MB8y`zH%1Iw`r4*lI2BC;3Y3T*wJzpQW8Ni zM2s|1*qjHTFW6% z=b!r~xM%sTaLiGHUwr!X>9A+do)#!=PVhOw!*n*Jkd8t1%&_BL_%Rjd)a8JZF-wYU zk|P^B%Uo~P&<@x<m z4IeU7iAy)!a6`poXwKaC=&^URXa1thT1MMeM4eX6IG-~Ypm+TbQos1!hc2sXK2iP~ ze*YavvgwS=JIi-?`&GHO>F3lcYLSf(B3r)eDBLc(hdqka zq^PRgielncfmPKYyw@yWDdyc1PyK=a+_h_0#D>0E>`EI7l#WK~=|wDr3r^{X0I2Bq zngmn^Vs3{XV75U`V4g8IfVbQ3Y2Oc$lmgV-tW$Q_1J2K_#=}$wxn{A`{tP=U^61 zITz0AaCk~XeXmV5ncYq-U}I{rsIr(C>C%pk1)C{0sCmRO2ps@6_Cw3}Zg;7gB)=zP zV`8zuqTyS z2cEx3U!Q---R?Y6e4LC~ZLHcBEfZR%^Re^rS7YYyzn+0Ev)YlF|2Rtp^VYE*i}p$7 z$9YIuNt2HlLaXs)uX z^Uw2T3u#^!IBQ5H5e8YNr>1Rv6sA4?XjQ|YSv>7SX;P@~vw+abG%A?B2sB8tLyX4G zA!(R{=$+KiYrPl>o>0aX#hbU8W4LGHbf0zB|2Mi#X@qE1@z9{;ypz(>kZSFrkr}Z= zf~1vGJ9Dt7uN3pq_~lqzY9aGD_|OWw2jE18lnXI>R+~=sFbYV885v3*(!Bn@3h39f zaS#^FY>OMEj{mRW8N~p_t1Mgjp{-Bvf#>(N2^&5uq7y}tp=dIci1fdtBSNW&PI;|5 zIDDLVQ2E;KyRA7d z>v!NKz_#DX0WR6g?#j&-pP+ek&?SH`{o1KNJr6tXw8ot*&;jM^d+wIqh8FoO)8i9m zn-U;Jk1v~eNbPpFBi*_bYQ##Qw1a}j6s-QlP#>26xBnA=)b*JDxAobl=Ws zWL=BL7BdX;W>Dcb3@9DFCw(;wPK%!*70lXATS)-lMBq6#?M{4(6sof%Lvhj=yZQ+c zjinYmi;a-ZI)A6;vlJ;_d2;^w?}8O8f69OFJnVAlf94nU9bo8#VB{)$Kds%6EFmSe z-AIwaxu@d_>s0pS0gyU8lKm4Cc}2%1l|g3k8aWgB zB)Oqy)hyq>jQ@VmBLlF1SAho>z})S;u7dMdIC*hS;mx;c-d}186*#~I1}JdGh$x}G zFCk4IADCv*>)kqFTa?x1KYsWiz+p2}KZi{OJ{umCjvmBTvP(4Qj>4*a%2AaBLOxa; z-!+}E?T&Bua3_z^r0cF<&40e(LyH=>!&qD+`o_4SHf2H3m6xmv`vzPo>GI`2hMbJ3 zH1O;#qZmzb;RCg0mbAfh*@Z(PEYkp~`bMFUe5Z;$pUG!gpgM_E zF?KJo@m*#r-S9-HP=K%Y3~H*Vdas(#?dybDVA=51DBsx~1$eA~$hBZ(wbX#y)~XER z!r|5(bUE6D~y|$ryiyTk3lt4#oQgmFT zCMMvNvm-Xq0$l#NZ;%N!a~WJs?acEIEfpCom{s8Rm|TmL3rkA7I>+MF9{-IHos&^Lq;Y= zbmC;+<$n9rx%*Fw6(mjqIBJOx8^a2WLF=RnIx|Yz*@Wx;_!35q7Cgp`je}eg8qP0j zqQENXI3*nw^Nm$L=qel+FOU2;95(B7FtG6-s-80~P}&qJ(ETm#d}8}xR;8KqYBuh| zR@2vEFTlVC5MvtAH&}wMjvT)kkv2xu=GBxZX}QJ3L4Zz}O&N#U6WN3$q{HPs?Yuce z|CHk*2oC(p|L*yHe;HI-8z6;Foz)g8PnvRK^l3X%#yaKF2v$OZ=yrG5aI~-PDep`vI^2(b}7A%Q3%f%5GH6Rg5_eghPg+ zbsr&)+ZJQy;Ob`{fU~T>cbsw+x4R8YU}<}gaQ=Ch!F?;zDcL5wYJXCJ(lAX+DCD7~ z+H4|plsu4GtY$uehBR<&O;%M+%wvD_<5%CjD`uDY0SpeE9Gla(zV)rl3&xdKUYWUs zWd9o6Em%Uoc=xAvAoN=lo_zx)=nVJ(5&aWlNxw`~P?;qRHL;Sh<2td34{r#N5>U(q zq@?uf1*dkvy^jpRw63_%#>alKzeSSf*PYQ0$+=X}43khqa{K>V#ed#-WC7#RWN?g4^rTiR$Q+mGS@qF5p|5|Ac}&B5j^h&xVlz zX+F<%*_D~u2?MY2`&*_QYz6#=pv`E#07TuTWWEGY^*IZ064!WPVq*Z{ox0Tetm|># zMggWZrqt+H@1a#dj9E)-V4ECwh>mR&W&o)&mtmgsfS!MxW7TlOf^P|`>qcu0@IV+u zX0H|wCO2-I9~7+LnZC zpEhSJFqfi=-=lyZJMZN8?pt}A#dF$1r7fG%R&vrOm+qHkcgk=l+k;nc8ip-Jmip@0 zoD&c>436+cnxt+D{E*$Hu-TM0VMOmkwwF?mMhhu}QdM8vTx8n&Uu_WFF0}mb+Ma&C zc+vgdfnoh^aX;LsSrvs{ouY1g`rP|;J)aX#aX?yPPWy-WL4%P_Fe*t%)n=xsPFTNobop)vpyadA|rZAg24$3&NFtr6QIE$&)v#@KX%`X@c7hMo5NjZujWxM8g=*z)-&^r^>M=Nh7JVC;xixP!9^N` zLcU-D+mu2e1ZlVEP<-KOQzX5b@UUlz02(3-4I<07nCw_)ekXuh$O{Q(l33SS$6`V! zCk0(dXctUbb6Ary={F514Y6!sl3`RcjfaYKj$>CKvkugstaPEY6I8&EI3?AhA)JMT zLy_X*;DK#=ZRyFrw zV4*YjF=7+tKW+a`>M}aCi@MqCx#9d%g$vO!^=uf9*>^3TQdF$JXz~sK0(7j!tZXn` z3zA-5czTDBI+W9yxt-t#Mx8nM3T%`C0WLhX1Md6dh_I(^#~7Yc({}5m>Yl!X7$}>U zj@kP>JT?6=lUH19acsPGh8*jNCT;k|U&66_pVh#hfGMSC4?MEw-z1Qm*(`IEcyVEc z&Tnan>@4{@QU-2IPEv8!Su}#X!%d2gaiq@EWs;I#Qor*WffC8Eg5pF5WUQrU6{XxZo5{JSRa=*&lpuUGTvqA3el{fdfT7QH^#-$I8UnKgM> zr%4A&<2$tF=hm1=c>;bKYmt8)$Sq^aMPBKy^LXW`h)cn|gT3$lUa_t z9x{LWz$|$C{Ed-k$gVcBsb`Rq#-*P7|37pQz+@}nbr1944l=`QS2m z$6sHhxj>T+4wVL`iJvM7_Y?YQ#?!sK`Qqe*oG7qte?#HwXcF>KOvMXR4Yl;>; z#I```1O}8f$vyB}D^2JFhMeYeM|SBxdlaUQaT$`sDzYlZpIf_>oT~6IA}LmT8?*i{ zPxN-TPMErtn3`)TvSk;wc4O4p$fs>e4g1OBzl@%<973w+1m8S=u<8UY*&$#`>C`1J zIp2$Sbc#Adl3i^meSg)=2sl0Kf?bfaO3NnUN^`=#ZO~sH3%C9LWO&o*kB;qPP_Inu zSE<=N@qCGdA@Ya45BMvf|6vXBB3VIjZJ6%k+NSJ=G3=pD3G9jN$ba ze;lxFJr9gQ>7Zvf@t-dqa-3@?>hJx`?ROTa1xxrHZJW{npR(p}wfUAk#|+hH%(hbv zG-fkOOuy4W$SSD&BPR>43ZJ*Y`?P1CE;5WbT=l60s z;jlBcGn+)Cdya85QuQX)q<^fZ=j;@UHN7yS6cwxNlZQs4j$x-QeI>KwVkPl?&c0wL zJaq4jii_EP$eUp3h1)8Vw5?q`W@G35XD8p^JoN~8s7FXm37AqEQ*hb@YhJdS7`~5V zQ=*#N4`-p03lwFf$ZE8nWDpQQRLP~xDlk*oqsI4IdWtPwZo`7oEGGy18S{I<^CC7> zMU$+4b+z!XO(IWmG8v?Q#UdNCrWxO_U{$$M>yW+VYtNiw*@KBT<4!u|bnl}>{As~c zn*1HIAuV~jS|0Jqqh1nVlR3}$wwL}U#;KMt!>SJzF@M6@7w+dqfWzR-Tin_=X|UuJIcGtS#CqZanm5D1v%kpP%isLS z%fX>RcAnRNJ<9lyL`i0|Jy0S$(a_U|f()H!C-OnCa_+|JW_p(I(40`V>Esa9vvJr9 z!Hm{WPY!2^@l2WKJ#NBXzXhGv0x}N})JvsUbNI^JSm|s6HujL@94Rh5_`+*p-fMp2 z+}fF zU<5XExg6L^v4tT(s;U{Px~;yqD5X-zacJ9MQO)2d-|<)cUpRdta%J%qXGi)iq?#A( zHevPs(DNcz_t5jV8n!ce`->}fbH}*6j`+kl*yaBu9T(Xha_2i~n@IN*BSR&LKrDsT zRo>2DT(Oe_Y64D*=aoRmh9Tn#EuvNB;j2CUyl!Wnw^R1JK>SbPp>^9x>PZR3LZKt; zPywat7X9Wr1Mz;%=N*#wVlgN0lg(&e+Ki$ksHc9(^ZUf%S;z}#A*ulH(_*fs#aG}u zGFh2vK}^`2<7m)4;{%6s$zfko6ocMEVbeqTz?9VYc_+N9tG-w2cXQXS8*{3P0mNYb zBg$@vA$8hD)5kGaP0!r#G3L=)wIrpJ7H6ArQtll~l z7LtJw>6neOoX#gQ68jf4|*B6XoEqDcLTHjA+tE#E&ftwz#Fsd6GtQcO*hD^7wa&M!b~R-Q2LMXqlAUZ4)h4tlZBFm}f4c6x zsPuT8$MQe?=tSBY5(~3t-&9!CW$Z`~pWDly-S@!j%Ret0H871G3NhZ2S?50{6W5JO zd+)39`XwMG8&X@soJRpl{dD1Jol>1hk{P*xGC^;m)$EqFi|=K>kW)js^My-DeLGXG z@+;|5bI>ZKI_g^Y>^5y8fIOe!_(isY@p|(^;jwXkxyx_3;fCb)4SfIn#qWpjK9qK_ zO6fGr(&aW47YpaX0;3>klV_;BNE#=&cac+QQNIXDC<~5B0-wC^h`xuUxb!{;ZWgtd zMN{V2ZPlt(uw==S(Jc@SzS%~2N16X?nq8=C3Zm8`8}vBzpLMK-3WXV66VV+9`dZLM zJ%-cR=DUL^cd$<*XPKVS@3ZGW!`F~kiZewRQ-7VEaWUX4cZfU=xP;R|fkidNwDEvj zINK}&o&H2kV+AI>OrRYg!K>ak^J%%>PYO_4iDz1vjzJ8B7q<^WWtMA=pAaou8ki_} zJiHOF?(2dhPugfsogi%9=FF|pC$j)bdsD%{M&qrkk>BjaDQwu}F2-pTA}N*P6nsVE zL}l>9)yMIx?_RVOHsoe_`vh82%?>Azo(%)sQA%%u=utz-w&GEi++C&&YB~g;p*mb> z&}tT79jytKGP} zQhPY-eb8`=qJGx`or+VGxkUL6Hz}C**W9K00Eaqi7uui}CE!QH=lsn({~bPj>6Or| zX;Mf^M@yT4ty4-vC0Yn)wdY5j&z4ej*Y7&wtuXNHE&TUcLpxwY`;1BlQ|(c5oCLv3 z_dGnPZAxjQ_|APtJNHR_kC5U$FE^Z!_k4&v-;YDjW6&#AD2AW$0V(Y_YqTwD^Q2L` zx+N)huwErgzI)kUE`j56RH$RB{`y~ibZOLHw*1jIUv&=Ldi_fH*k3IzA4uOjsVyr4T`(_>K7m9KkE^!pwc4(nR65r7bs>} zzpTn7jiFnvTTxM|{^V1az`SyMQ?LsHwF~BinE}?756=Xg5ri!-alDeLmTXRaec{ziF5PweUp&SxNd^R|2d=gIp#zsfuJzrJ`U{N1N7hS?qD z8_))yI&c4AgKXbA%;%{8^5e=ea-u(b8liMLu}fK*2Y5l(om^>n{7RkZBt5#=#iM@DOGixa`;;S zHvbgPzu=v`IdA*b4r85W|G*cKkj`lj9)x_UPj@DQeF|OJ&b^7py44$IeoCR$ zZ@&Ft#dWy!LyLr}v{V#QEAGWz6rpqJfGSm~j`w{TOyp5S4k8Dt`6m>{d?{#ntN%Dj zX_6(6yzuH5Hp9rc2r~v@(VR|MjCjscCK)40Qu(*%>>smSnhWpwLOWc1@x{UXZoc{E zisz&)Ise{+?mO>2`}P_Pz^+JDR7|$|ehWz5=%X%v=})a3_O$|Hxg>!rL!74!*LwPdC@6&YhlZW_mYX z*;1^k49Dk&;zs!WB&olk z@F^K*9In34>q)U@{lLWNAFp4)qSNrtA@8RXFjl@Qp#4oR&-?du!jdvDrElH#$XWXO zW4UR`D$z8~G3L=p#p-raXn_Lhg3~%2X=hLGpq3PnZ5x46eV;|^y>M2W`+1v=#tSdH zrkt0c7E(a7jpuFK|Jzbj^|~t|W!$ML)QsH@5x;nuOH&&h2c1-W1qS;|+$7|ucWwo; z_TAd`s!Z>GH-<@o9Q|&*@y3eFGH334Vx>>L>%X6Rc!~rkK?nuNtnGRLU~#`a;F1n^p-7wNv@u`pqxHoZ}C2_Rhw`28xzR(N$R^LQ_>S!&1!RmS|?vm_}&@)iq5O z#o)XpZ-l#--=ZCP>F10Y!u)FQ-n}hQ+VJ2rhD^Ve;^X;F$O2Y!ZaE8(*HDv zKjR75^1Ea7JbLb+qa;bZmHC0Mhd2J^VmN6EsoW14Rk7dv(Q~;Y6AKs=+jOc8zt=K1 zFn|Kz>Y&Xc2QswyR^7Pv`W4q`q5c% z?E2|?J}+oVNabJhctp`!1e3$-MQL;d52;c4+B~Hika9IVf?qkR3xdrz1aovnV;lu$P9mO}%Dk^Vx9+RvtjvcJ3H{$H9fqjCt`xAHdlz(rR`N3!Ni zO%u^6j`Oj$5y%@2qC%n_)0mgWBbau8qZOKQ)nkLOZM^_2*Iij1SLH`<+73_Wb3DH# zbK8TRe$>gEl3S$wY~M4#;F3U10AId#?>#@#MB@akM8qfqzSeCT0dQFGqNIiBN8a&@ z=Q4}4CITr{JPVLAE9#O@a$IUl}+{IBbQKE_7VmSPwcv=8j zb3^fzCV^J4>%!cD;Mk;Mehe$^`4ZCApD)HwT+?}>ol&>UdWIc zzDlV%@JZnfK|Sa)rCBJkSMG37Vy)~ueg04X(5U`=X<$E?i}mDttxx*=6+$a;UC#h_ z(n9+H6sa$|$8bcKb5>KGx?Hl;wm!;#?mTL)dq4rhhiZe^mVOstQp$!alccu1;T!HG zl}G66%=3TMrmiW(Q?o=Sl!7z!s&<7B1I!``AF5nwM|8U;jc@A@bu(_mstSH-`|ARhFxHQkOWcS5vAJ)X3%dro`m7y6(11^;KKfoFeF^(Nz#Cx#<*)Z-rG!MLvb z?08<&v~+xqP0I1NyT|Z0?&-OBLX}jg;;nw&I5eTA>;%a!C2t(Z(u_?#C-07lDYxAF z?I(P;y3-XlKBydRnlv`0ah=Cn64Hh{jAFv6+)uw=`MmS@8_o%Poc?;{bKaG%x>tvQ z*P7me2=H2bVkdm8yOY=SV+*Ii)i;wZTHev(eawq2bM@mzc=P4|1h?Mu_we!VDf;@0 zn}#B1OJ$8pzicY`fYdk~C7t&L@I(0I;{8k+p4{bh2rq{$^wm$8oTyGJy}X$WTwO`Z zHSaS3=gX`2YKd?2d73uX+H}no)8Sp;-K~pGeb!xPl|3DtmYg)D;dimgLtbYxufm1f@v> z#1NOTiblZ=|FU6nwL?<%i3@L>)G#4RrL4Qg{ZCABmc%!l6Zc$K)O1Txf7t43W;4UE z*n^E>kYPdIM#V?Ba8|qKfK@!DTt&U8%h~KHz52Wr@PR)+J+`g{NUwR{^jN@Pr%&I! zOP7<%z#S_1@j{WZP^VYG*{ae54?Hj? zV>jND+c>^F)-M*Ldxw}1_&M~zOUftJ zU-En3`&54tdJJB$Z~eX%JL206K8lu9MJz?a}lEBA0OaEe-_HW~5)-#Ap{_my{KE}u&^US|N6 z#~2UXBUS#|^~QFy{n=N;pMKuj64Yk+h1Zt%t1pLBColx@(RTm_4jGDX%m^4|LC|+iz<%!kedvYACaa#m{_ATh z8lxY*YH_S==<1te?qJ+FF{i*jIVAr4`W^5eR~^tW8#slXUHw>}0gdG`RZxJt222Um zpO@eCk~1U~X?Z;aUQ7YM8mUStm$tT?!-I^>l%Cm~t}MW?anKt8Uiy`5*-fDEpx0}_ z86gZs37Ngqm^S>!iGV^Y3l-&zN+{onJ#A{<*nV|DnJ66%GX4jlioLToNn zH{$j~8Igq~k*vsgEO)v_2a{^J|E{}!HC%kS-Mx4ZM2j1D-9bpH0pFvm!Bz~JiQ z1nIo{tjTSC|FAfumiw!aFK{U~KV)nkf{fzDSf_cft1Z4tLmR}HOFd*$!zqdu&D`=(Yu--N}G<$E$YJ zYnbX9i}FwJRp?McVUxSyPbyFvQKJUd43@aeOjbmm0JtYeBXr9!uaP1J%1r=Ife$4q zCE!7PoW4_=WZM*uN1CfMC%}VTfOy0qd#T4%Ol(nkqIVyiT?ut$CyzXTjE8}tjlvl4 z2i~?nej^q`h2rrO=(fR)d@@xzPZm)}^OxlFGsgJzq+U4x52InhNQ`mhK`;5WbP;}tmczr1LbeLUDA-^ql3n+b;r5yPjPhq=jUwzs^qG5Bq!(|Zd$(8 zjRQ(YrxL)*ZCzS}WBhkMtm2(fOTH`p@WhvLDG&Ij2nLb%jC}0U4=sZEGYiu6L#V~_ zQql?Xuu>`tX(t_ma+tFurD8oQk~FlK=W7ey=b%%CXq8e@ioO$eN zuwpE&=UGjfF3qg8xuo;;?`^E`PGmsfSeI>bCz1j`u%)PldvWu^ZXYrw5s}W)Cl~== zADC7;N?%x5BI9OF3OgArvXnf+ihgVJngyUKLejkviC4!T6>r@-DxRlkZ0kJ{-qaa^#v z6`+;IuInq4l#b`HtTe4%yLQal_x)#A_a2$1Jg{*j)2gfPRYEDXP)lSn+ln6ZKz#f* z-)c3k+?WkNc-gFd=0g5+{vmf~7(>y_S3cSWM~u9V|9LTp41R<^`vd4wSN3-lNJ+FOy+N z*da7eDg)F%i~%?2Se?*={p25ASz14ieJ`JX!MkA14_Ay!d-=^ns?pU%@536a>ysp< z9fw>FLoeKxDB6kIC5CdXTt03*#IfQ$uD;pCP4|m(z>Hn7o10>WbEM|c_=j1-v`g`&FgD<=m=Dp@O{C85{=bd`E$#?RKvoY1< z4^tLfmQcAW!tRA0zx<=;@`4D^nlB%CI<+|sfl30HbU-PT@7ulwD!n`~&Gc2EsDezu z-5l1fyB+48kawS&@w((PJ9)E|im~Vz3iUkq=x3=IXELks8v>Ljof@*7D3~{)E;ywl zeKVQ_sFY&Fr*7_6J;$03D)VZ^68b(9zyNE)y9+>cJ79XVVurxZ%U3?ZLJKjo=tSIw z@7Wjo;Hiy2hE6zSe83zNJd;G1CC%@+q>5CIBHSpBE6-qe#DOi(%eF>(c}Kvd)nm%x zZ1DM8v=^(*329zqT0YJ+JE5$(^oCa(77L6EL(c+H$|@!iucFWKi|lYdn)lcD4+`5v zlI+O3lQgL$H(*M6eqXi?w`VOmwwINp&B|`FB<&_80LbTsJuR^Tl;rn$dtnaV{_i_r z(TP)}U8c26Qk$XSUnJn@9&{`!Avs@}w=mP#TY7TAv@^5%MS}-s`c!ijf%R?iY=|jS z^MOi?tsKr02D4dx4u6_s2-*%sq1Lkq3KVAlvuKg$3l;#;TW0F~A;q8hM zF4N$m=Fk|4zaQ-z;A4r#6!k00e*Mz@dju;56NeWrEzB2SO9^zJb9-PW#$4$8iatyC z74vyYnW+n9lmn+N756H$CW)cuQoO738_d3Lo?9@hjn4;eODso+ki=4%^QK=cPEdNM zxc}>cZNF2_w>)ReKoATV$_84Lv)uMOmI2G=~^Q>?TMV(cap$o`EqHLZNv?4U3Dz}Xxu z5%3U^k0hv-PFm#HLmuqHNy`9!mMUv>#q0E=rwks63M#gA5+sr;f7N6C;20fxqEi3; zH5&$D@tlruyBj>q$M9;(n|bnACx4bGDfd+Jgr5A6HyieDUJ?+>0{pAmLz~SU1MWEB>LX|wGs&w6p-V6^sAb3r?yWb3} zSKs2z9JGFCF>`_?Pa5X7i`{lv4!A+FkQ#H$l}xjMG*U|qt@~`oB>=nb;(t$nay{%i z`b5*^JC+5UAv@dHGUecxjrP=K<5-ijv!C1)WGFaeE zK-=of{M#7nH=F;@rD`&2k&s=OB#*Lq_FPJ#Yy+a}@VCMV&)f_nL*~ot3qtjI_-nf0 zh(i&6_x#wl=R%8aYf8C%$8Y;j$7!OsFr5#0B1O;V$3E1jvMcO7^evIHZR$8s(rIR?8hA!XSTt`eYKkW2jsmCS(FPS5b$-^Q)qvJBCQpBiIFvGha@lk+)Gs9-b`YgQ zjfh%=l7p2;eUf1bxg^t;lom^x3JpPUq=L<}XnmN>H1d|Jld1QWBoxrt*YW$pL!E;^ zYcA051aKG3DnyqJiEY<*~8-PR{)*SOd`V_!j@;@06J1q$MP& zh3Gu84;gkHL5y9O%hRPrLYr4f(O)6z_f%Qdl@FnGFK5lUoaXTaD}R$`j-;FP>&|8H z>KC@^_L~0WWBliiBW4Ndvu=62{}`7nGqZFUx+Yn6b>GZyv-^~-?!>- z+6FDmfq< z;3N9@DKCE?hV#O(Uh$^S9oY?!<))2uYl`;#%VY0?WzUL5Snc_9Ms^8cI?m~&m%a;w zUYpJw+zuPtX9R|-&r^z#o{f$V@yxF(;3!qekmu(maEdxjt=%{XdCUtQQb`F_k{djQ z;*4+@B09jx<+8+trN}1k#+bQ}4&Zh<6w!b%1`(j7@+5Gurgty`*vSr*D4p!@guYJ_ zQwkV?7?{!y*}f?sf!_Hu^RdzaT~-Yq3}|ryrYG%0w~g(Z+I{KQ$8l`Z_ifyWA%7`A z^v=6}-^Q%H8e}o6E)WG_I^3!k?885D1=mCL+S4O^H_?N@J&f5T?+zG8cdhgffWcFv zKaUMtJ=&d!UJw&`7_sMjlqZ^HlVW&>M4J~jdca`TeP#s~0P~AKp6#)Ofwn*scz_Os zoFWY~GQvz^DQfe2-(!|{8av&;X9^^R)t-9f+ZqppR}#iBC1O)OhF4w!(n1MgsC){z zXVU_>aOS!R(|ju*dLBp^N>cP?z4Q6CiBi6tmP#?WJE7f<&&kH-oS-@Q+jIAibjZyQ zT^4!oO{a>VNw(8*3;pG1{IB5k_s=t`)~lb`ZQuZRGR*UT>-#H<q*T2eaeSP}BJHiUTcBMKTa6n zCjhC5QbgrDY|i=#P&R}+9-HU18>J&o>}{$=`MG_anz-K(%v<0C6sRnU5TytfIFaDP za+ETTObVQow4;;)Ugkb%P+I;iGStxnrVBGrI+0n(gIkIf&-KcdD5EmSO(G8gUTfvFOd7I-sG!;{|kfC9KWZ{I!dK*`4ifl)oaW2Y=1HQ<>0<>)Tx^} zFn#F7*EzuSE35Xp-NCXCNK7bRSYN@Mjvq(3+XAHx0AE|ZKFL#Pf|IRh-?pEbzmIq; z^gr{9ntYG)-Y4^3y{`)vb@e&-51sQEbRJ6I`}w%HP0zqIc>0gC9EspW0Hl;27>?2o zk#io4F+1V(HWO$y_v5;MdX!|{vpWj$>z9-gM+GfPWM975mJ76-+$afTwdFkljb)>f z7gAnzlcF?*nwnEO&FKtIz)zh!-TZM*xjk+cp)dWiQ`#Z}AsvSdKC!q9d`fXUy|`%* zdW+(Pxl`KVlS}psKB@k?`YF*5Tg!OscwQ}4H~(2CPi^A-)oDO4ek4W&gy-uUqgNC^{Z2mayd2@MV|^TPXgp6S=a`d(2fqE)11<)eK#Y0yFpO_3LN8}Os~7?pgT%H8)2ACwL6Xp)f9_=w zD!FDP(VsAq(t0+22Fgo^Uu`m?*4PD*O^mv-(1b-y+{~G!hvCvnGDonupzI}!q@*fK z0+H&JZ~8sD@VdNv7B>zG_mTc>KaT~#3hb$DNlMC{KE{Ekw5JRjNXxs3D4}FQk2+-& z|Fu{$^(J*}tn{Of$%*V!F3z#13C~&5B(lf?F4718;%qJ{-LYCk%AubGOx52La)Xy+ z2kjkSad0wguy}RVgy)zn^GTOBRsP=9H}AGUBjcX@WHPX3eV-)`V%#ChA;FJXQhf4u zMeZ&rUQ3x}MXU<$HhT>;!2n{UtL1VrOV*VXJb>zC>cLztQ;T<0NZd*ur5H=-V@&U( zYTgNq2SuLGO*RxKCmIe?Ue=Q8D8nUc^SC;^ql`t?R&lN5K0~~nIU56%bpG5n+Wx-v zJx%-PaDmDeEeVM?jniC?2_qDXOO^k={Z1nCHt+MYxMkwD*P1ic)L-+MvXWpyP|U~7 z<7k!7f!z+WZA)0O@XiBC}M6rYEe( zi=yF>4cp?mQ=GyP808D3rb`)*vJoIgSaM>Q(`>|z>1;d+c}zq=8k9KV*bj^S=6^E{ znFQ1I^D2KQ0}9gVYiC#f&R5T>?44`Rth{VrIis?7{`K_g+n`?Wl>YF+_%+MRTA7}F z`TjkwBNQj!cO9X)J#L9C1%wlrO(PeHBf`>Z!5r1NM-dvkkP7X|pmqYIWbAQE&^@;! zSXH8$;$W3qX%sYfFV%P635A5Visuz(o~+m9X>|#DS&C3dKivv5+Jq@UBgmrMKa;Au z{xB!+du|KKaN?B@F?jc^wtg5MDW5W>LvL@}bR9)Uk?)~RL#p@;kp%@t!T~^1Bt;|* z2&dpK7%mzKx}bKlXhYDF*fQ&Vo63ZZep|0a>ni#ZPDC#kV&zDK8DoFfyPRt|KcR`0 zZTKQ_+)Gz!Qqr$4uGr=Bb)ru-gf5p6;sjlP7__Y3Ci%8#^EBI3S(0kWaJDk=c~|{+ z(c^ekT&7C&7<{LE|LPClRdKoB{kIo;`B~pb#VL!LlT^*KoJHk?yl9GkO3cul;@+jd z<$b+9S^Tq%SV~dSujSNEl7nfF8wb}NN6vBhX&u@q#8`T@W&@}V1xl;!oDd&nlz~B_ zipfJ$3ZJ=Zc@WqU7$qkk*ZY0~9vA|BQ9c;+1!j0y^yr-7U9djCe>j5xIlfDO>XYL~ zJDx(d(y&v6?k5)al!5S!q*q+f5y9Cwj!lXX_~AZ;{0;A($J2=|3bpJsp7E!B6e)Xu(>9@zbA+|aNCB88_$pZ(yU=dCx!RD4@7Ol>iA*RT2vZtu;v6gJxMPWAgy-k%>2Ea z_}*QTcXYHP=gx2SOz1YgAYHwiK$DO|?*feG8Tl$L$# zfeBl-W=h=|2z><>nEw|iK^YWyo=OBMK7OO!?lgKOV|Z*cxrQE%e- z9Q`OpibwLA05Lf|_T^Q3Ha-| z*=X9GdEA|iG)GliJ=QOy9yx^H%pL1!*y-7%UyWKRJ477gLx%&dEWS~jds6{XW;i+Z z{>mC_=zhMuZhm!5Kd(0r?W%ZYB?T7CNdZQQ8ID%Tlgjxdv-^r z@?L!9eCO|v%D$HplYacdj0?D=FAKy)cLqdz?7t? zLhXm5e49p01EMKsqwCg!K&8#O$q+?jzXE>XFP63=PQ+CXL9iKo=(dPR@tR9wp$eo`c! z(~?U^)ugE*L20EYh7eC_DrTLei4*4YaGZubpS;U2xZvFYFHQttN-FPRSaf3EBcx{m zJdMW25LqJFwaNAEaiJrM#E{&JZ%A@|n^RJ)9V}YJ9!>zCa|+Qt$CXyT^E(2Nl3ItW ziI^a*zT%Qm#PJhdBUA9rA6U9zwMr1F%uOh{X443^=@;XZUu3J5jg$lq(R-`86; zt@&8d4jN#G6k$fFVMoArI85CDB#{Fsc)-~C_krctaTKx-3M}2tg6*u;_5R( z0Z4OsSIkK9!dc1WPNoWwu*k-#+n3+_W4Q35KY_vLZ;h42*@?^{H0ZPPUblI8RQ;8uRxe!C(E2$in?`kIRB z`_ZdhGlsZW^tS0lWpNT(s_IsnK&UiDI#Vm*&9Y_7;NtNhD^1)tVrqvO8>iaOTMGvL zckQ~n;KP?**#f0aek^o`+TN#r+FGE-?4-)L6puuawjCz@zHnB1?T}|xups*a#AC~2 z&I5t%T%u?I+pvxm{i|=R*4LFi=Ryhg{_Z39!so9)Kk|)x%fNK;iJkoSzrX4}ef@Qw zJ?JmLu?jBz@S+IlQ{U*>FkE@NTDK`$*ypZ0SO0z2w}oVqB&9r*X&IQ#pH*<$L8<4d z-j{yZ0KL!swP}Zcy8b*4OvynkF2#XLvWw=DSjd%otpuf_a9&X3m!!ORezS6(*z2xe z&HIPUE+`Kr#ikhG6bh9j8`STc%D?APNcc%g%>NaOtp%i&8g5%;qkN*_0Rd|rBgZQ> zoTF2c^t0Jw#MU2>jeR0O;sd?(60*uFftAj8onc(Ut(y6cVLg|G^;Dx!#7 ziAg}YAqVbXL==*M%8`(R1PJ7q$;@>9`>XS->gs;|=1peiz1Ibu*VElqT~%FG-><%^ z@AnCLpRP}im*nbI(J~h<_aKE*n}?Rvl%_m9`Mig;&9r-47;O|DTmlkp zl!IY`(3o~O-_z_n`VpvFunw-vfgC=Hk)dnr$8mf$M&GLkzzk?Qnz3F_yY-GUXXyw zVh5ER*$91^9eN!;Y|HV=1;IAwkwe49JxZ>23{mTLF5X&Gx*O`fh<6@Xcw1E!Arvk>1_w~mq@N6a(ezkh__mfpUXI};DbIYDR!%)#M#bQ>uEc|eB07fv8d;ah6FDj{~W$xYKdW5TN$bH&#Q zhWps`CHx~++@4JbsBE9~Ia#qxF%Yl_x{Tn0NLo*1(itlwQFEWBC2(o%fl+YM-a1&Q z1f}J$ScbZS)@k_$Kec#2izm(+i(g0dg{eGeNB+VkM@Y~}_KFq_6qpvt4+7KAf9xKi z>BRk@zx&Z2YPvx!%6D2MbkpqvUX}RE{`hQ1g?Z)Z&8$jR$JIuj#OJyuo*_;;C!Q`2 z9rU@q=It3_^}l$V?%T@2p$x+__-5T^HKH`FM;capJQ)mI8`~NqPiu#kTfWbl6$ELa z+NurM&FM%5wOP5qO!v6aFeqB&HzNT;bcuQ4(mv@OM|XIhP50$HUGiynQv3B;fi~lj zb)5Xc>2fxlOob7&X&zFhxk_^eble|_-mGXoaQS_nzxPqymlPwGdIa}x;&Q*{Sw&Eb zTL9?$I8dHeR^I^0=6w_zRVs!9Mz~v5RYW?TbS*0RNV!QfQuP&yReE;}0Tut4gT}yJ z5BETvJQHyyJVLdKccv1Qdf~F0e_%Flhky&KXG3=r2VAnG0l7(W{~i_+0V+K9i_tk% zS9k)Kw-=D5V$_n&m^voRXURNl%d^3!A;w9ak}cnr~5K7AaKNXflK(h zZY4PE0OO++QlS8uN?|Nr?P zCpz!>Z_nLv?H162>0Q#qx1NVSYH@1-2CteB#$1f@-= z9WBiTvSFWY_msDEGzSExbPpqfr9wQWS?ndO5G>9N2j{!PyNv0H8Y3+ZrY@D7d}-O60w~3&H(8>E6rnS%f_5ZK(}YDkH8c)*p`Eo!HMTg zgTwb9Ys!wA;{}iQcwoKPP+e&-jNcY5+%@sP`#c)C$ugo=7zH32!C~JX7?6fYank?M zh)a|6`)ynYj4vDyfHGn*hEiM!;EJ5A1;T53){5V!x7}^fZTM9$trWk{Z1>7?5Guo{ zml2K3kRILCt3Yd2tsF7YSJ8M-gIdvF^?e)OH8g$rZgc=LAkyc8-mRlrHRBb7^a?!#U+2LxQ3cE6F=fRaf3*9Av|4t*c5NEX zS3be7Nv!gzwl1wPJ4Vk;vS-&HzB8!7@-@r#1T<8Vpf5l8T%G{sQA`KKGZu{AJkk zG;Z9uLB*p!-1QQ6C?H@(YM{XcTwbQ2HVfBk@TZsGkq$`%FP*u>r z+aev-0}AZwrGLMQct#zH_+;Wi$@{ayy-ywvNA7)p0SM4|I_3J#XoYSg5oe?n0CE+o zTCIpBd<}%e@_a0*)==|@n$D`$ger#;QWL6HACmahB)+ELlgs-R1Fle0saG#zbsvGJ zbVz~mJ2Gnx#~unwrKVJAVl#TtG^BbH_rYpXBbhqJbpc>bU#!89QDl`i>zPn_+X0NW z1t`7yo;hk?NEU}$_8@Wj*O#_bUAz`H!Xq$_bT-9TN$R3nd05Pt>zU#f?k07)Tx0|g z@&GXHg2j(ZkaF^Q($EO^M;gyP$smPVFC>^3;Db;jF=G9s`6~4iuE=Kc0D?;me6q5r z0VNtb9h$uRVr5{2hD!6b!49D;q8zDQ1J>js0!z*HsRL>_&EBKn*vB0}uEDSqUvaEb z`W6P1>vM(>0tgIIfCwX{6i+F42WB3IP6#GZQ^`nd+-e~}r^>|i$sNX{la7ne9IAk+ zs2?shtJ2#PsW=tTW7FaLjTMuI5JSPNbEHQnv#o;&4z9pEE)|OS0fVP6UUsC_x~Mw4 zZOL@iE&%R(N`n6*_PP(AoUm({_gL+px!mVKLUk(<(d+xt1T=4wuTPN=tA}tV zzsQi*bGh%4xFkhDiNFQH#}^$#B5%!xryGQ}Fvs|Kp4E^L*wJQp@g+xyyC)?;6^(^b zxpqLYyoW%GdKyAd%TRN`UA9s^kTOl{pPVBgKa>#IYv5K%fRzv!srU0dRib;H`E7!G zn&`W8KdW$YngCVY^QvE~zfVY0O9Os8)VA^z`6vj3H{V!l=KBs26)VcEz^>Tm8~koO z75{VJk|191M>Ra9L_0yX6i;n45v7qM039&NT|LMj`nI!kGo?{VWs7l_LU+^}H@(cmM?I z`z9U5oRQ*Gb$Lc*pJNW-rXVtQ=A4A1SODgVI;Wr(46vuXuR8BooJggmL2c}Cowj!q zY&f}t060TU=E=$siE>7SlJs46VnBc^EZB{WDEBC_8u>6b0byjdZ-?CH zr3{vETSX*{g_!eA4)vDl^-|SJ2eadAIe+)#|1+9W{R}Sm z<8quaWJ0R0Xh19#`t|nZPss0}CoiVN$;ob$ABB}m_sg#umVG&EBzn~Wk0<%dX(A== zE5k^R#Vp+@DNR(~I3XrpjAsrbVKNlLb`lT;+QOZMQt)ZjLOstfL+IxACjwhHPpVu~ z%os`7;RIl7=gC{iv+(lo-S;vej46JetTjJNNit=LpZsymQK!qT5jlf(t1soZ?D9S5 zJl(NU?Udz$q6@xopb&sN?zm&~k28e!h%v8oG6o~2DmGlB3U)FVjBfmTF!!oGEbbQqK;qv{(%78}Snx{Yy3js?t=u&MVE-Pzyb;vWS!K${B zr-Qvtm2!1jBPAJM-#a;F2xZF|;`*fI`C@y45-gOb)M+!!elo83NOc~y_D{GPRg(o> z&v-5v3dr|G5Gf2AblXhg&Cs+`Ds2SZIt|ozYU_E;k2?R#MGEk$fuFfRd>)A}w9NZd zMZN3zXb2@KrCgp;1g6r>Xa!hB)_=!tr$f)PH;Hp3$nRS{n|xzg2c7uLikrpt-KQ)O z`|GrIe;lWIO1m(f=jH@aDH7)kp3=6`W0qRkk&qLN(juvIy`9MA^HiLjkp+X|`i>_h z;BKxNvox0{ykb@Y>VB*G6}NrG<2j`$E@G4m)eho@KXk_=&Go+{T&k7_R9~}sl~i#~ z-qkzA^gT%jRDKPw^A1V+FWqkO0%NK8jOh`Q@R#beBQ-999UsN>+a~~b!yT6A6f=>G z33uN++kn#d&-}NxY=fiTqf;YVPgYQARVzII{PRuyk@q^_iPY40{2phggyLwLs#^fZ z2KDiTp%NQ}HWReDsgy%rq_A$OV}j3r>o5z< z2{Con=RQ@@d5JVQ#-HH;d&*Oq(J~VddaJqCyXqDa)p8snfqo}?d?Mc=Yf>zpUo$(i zsE z?+dp(ME)8yyV_Ic0LJu~X8SuM8ddT4`rB;@U;LfD{^IR6@63HS^D2G#Y&8Lk*OKD2OAF(l_O1(GnW1m03>=`kQEScS0IDKqkq*OQTW5pl1 zS$vB+Ac1~UDOn18a1v7@NxP1&`Fl- z6ZeD)YtkA#rFoY5f(nX-xm8$!_&(2Q*1K^})S=4I2|$tOCwa%Z3on#0IO)9UhW9U2 zGkHx4fhhuhsxh_Rx~%2?boBg05|Y;YeWGp+=OLsm_;LANfLNuujnPVYK<@p*Jmdc0 z2cPKAN>YL(qW{nBG!%0;O)S49zqS*J`;%TtaO7^kcAo&nZL`lmOd^)!!i) zUAYNssj&a=yy^*9_sV_KaUsk_N>{n+?Y$HJ{)qTpzt{ed@5_{BDlkG=r&X8mn;Mi3 z*GwYQ3VU?bM*Z5t779oeg;wZhUm-~D%I--Wx#I?I0m$myK4)bpXiX^wO3fsBNb`9@ zYx9}rw{L$59x0u0GNP^WQ#__#F++P&EigVjbL`aV`$k~sCNzsXm4ZP3y))nc22oaA ze%J3ti+=z6;xapaE6U$0JWhqaab~@{b%vz5; zJaX=kwWaNsyNooeciy{UMg6X8o`Al7naFm}ED^uYP5h@U`^vyXnb$RZ?zr6AR=ncb z$HnigKEO+HR|Y?Y!@Tzy`H>76hgFFm+r_o}U$P&uQBFUWPdVepCd-sLjg* zd-WDE>wbuz)%uPnppu6Z%(H-}npWR}J-ck&0A&}@@|r+6#4{=^_cdJ<1Zb-{INx}N z@$QvPhpi3RXt+Ij_ssVnV)m6%_J{oM#0S-qvpL9l11UGlKvbgXW(__d6@c=&Ct>Zx z*W|Kw*81`qkminuUIIL?7xEB4aXoF12j3keD&hGl@1Q`ob8Yz&So_L-)3ype(FoI4 z`|ZO|+OnY3;RVZWaG{pYAzKR4lhHT8a-P!ho%>rQ>VrDhyw^ zA4%(ZP9lcDF=~0I?bG4(In>l5FrM>+`xOsssNX09uH+QA4p2iST_&d1-xe%U zZctO*jXQjb`q_$hQ_6@NQ9+1pD_?FOkayBO~9ww zvJ@~7py1-nYF^S5UDiCgRHBq&B&GwDW{Lj&;Hu-z`1pohf9J|u&Pfxd@mZReQ}-x! zO{aV4#NV4VcV7K>qlJwXrIQ(sNcxhA%5sl7@1}gG>gA9BVbA1uPdH?k+nq9hw0jI( zwrI2B9Yx#w5apDmaMH9-44*`5xX9K;3|5v@Ui~@f?CgZiOFx&YV@szc`Jp%&%fw$X zEA*{e5wKRA z@cx^xc~R`|lRS5%bBnl4?zv=Oc^-NCqdA}|qpm~RFAcQJQZi5DgS@KayqG3aq|eh0 z2f<#%LQ708_zzjY({Qp*A2{JD^#q6)$MBSrfuBM-A2d6Y8hS97Cl!1)ix7V-_s_ZO z0DyeZP?d`92MQGG`-_(L3eZmhT%ML!fLg+3XeR_N_{VGA#MLQoA;A5rhfN(L+cXbN z*0@twoCsS;@xpQkxEd~A&K!d7RJ&skY*S?@!*GcZ>c@eO+j$^1r4%AW`wnNRp6GH( zSEtiOaH@gnnq6Kk!5RlbsLvb#>?kHQuyc4+)flGk<7-~?`lsM;f7}cHZ_Nn~Fuioa zCY6?A=Z^`Ay$5;?*}mcWN1KGm0s^8)S+nI=uzSZlGc>FSw&Nt*ktF?(-S@TgqC(rc z8D$OVI-8wK&@VfJN8#PuP$x;yX$Zk%IYZPVRV0kOA|pX5=%l{s#eToZ9pN01J?xE$ zUtC@nnoi}F2wipxL!HR|IE#cqOINYa7TO@sYdoJK-ph!@TmXgIylw-!7(DoRp9K8O zvmgbY-T)u8#UTbt0Xje2UVy+90dde0Kg5#8!P$sU-{rg_VAUF?)k>QZASjd*9c2mY zEzfJCHLNGS*B5zAjggul&#y>BrBLBj=0sYPyNZ2#R-<903hx?+;rEif->iTc*hq{m z<&t`1b*`i&^?g=It+hUJyU2)SMBsFMc-pM)Lbr8mKHcE8b+`(#}N;K zu}*p*WEtWlgWi!?+-GVP$yjB~;FYXnzQ{^(wOVU?o-tNzcfi+S{Ue_i=j-q*M@ z|1OvXoU+NdddWXe%PXz>88|9W#ht>HYgIqceWjWsRn(q(y>vZl1sJ9?UGtcNZyg)v zDaDYrCsx1z#B*ey#Yxy{^{Uxf8e|p`Mq71MKVC`=EKs9-Hq{L}ggVaF4bbdvFY{cXwpNaQA2Fj{Mr|qU#}~g=Y$b};-!8{=t^5&Os3#`pvrT#ukhX9C9~GdqQ7ifos4yU+ zE=`>0cA|z#Y{N4*z@^V9b^HSdIzGmu1qYdq?eEiJipbZ@uu}IuO{H3bFw5sid{nWt zJ+WD90cQr5LgPH6I3zAoMQO?(s^xMx>>&*b>AYO}ruQ_a!a_QOW`}1`ADMgy3P8Yt zpD|s2)UFB2Aq93jsvycHwhtu7sUJEV=6wJDOkh<_>KM27aHd?!ft<}&lomE*Y(#+% zwM1uisAui>b~oOUsY98{~3+V2$yzktzsvW&J&cuJji$wG=&7K~fs(NY6Ef~eF}*D!D5 z9N;g0{x;>sDY^Xoe0vLNovIb5Us|41tCGdDqYvzHfgb0!hrDo`9E0!|JZB!v@#A3? zog}~F{tmN%W8PHyYbL(NkmfU*7XxI~r1r(%0q9jhH5S_2EaiyC_uDF-Qsti+!FWYXD5BhK_~iO^RV7XQucoCD+=66eNbV*^2@-AbgO^@quogKt7R_?vpgQIY=8j;HvY;c3~|jA6IRoOZ~7kdH{BaJ*f;2KVfWZV zb-8BQ7FZT=GX9!KzVqWV#s%YD^n~&llmNVCTip1ssgS`cx&O(-Czvc;^yGS{Jdei^ zcsE(VPtHGi#5U&MfBZwmSE|irv0E?uc0^8Hf8y}*HqTGKM5=_t69M1q`&QizSD5!u zdsJ$Lj zw%-zzHVAfTckGGYS|EurbE<2tEJ3m{W zo&LMG4Gv^qQR%W!eD3Bgou-?oH~-|t;0MYoyUdeJ_@bY#H-j=S5Z5gez+10*DcCl$ z-%aZ6r!S=je#Gec@Al#c*cJ-En`gARfF=F|%U!bl>2O!3wzRhB9GVfM6oX|LbYt0t{TqWoEn-duD1;E zRNV!s05j{~WdUkeH=|M0^qrg!lzT69&O`GZp5h*?R+uVC;d02 zN8*;Q$=Ewk{!qpH96DlkAAt}>8vDQcer&Iq`?1Gk8p?0%{>I!* zCsY@H8Mq(EyfY@_hvHE-_w{+4rrK*WfZEcUQaU-~dD9e6_G!DJN~DdBl3%qP_~(}% zgMWTSngEq&c!F?*dmuc$ax*M{kwIU742SP$z0x3;B4Ys*3h9}ZKOL1eQZoLHe>_;+ z*?sB~a5+FJPbp8mhVjsQ+&L^avu7TdH@nkA1f~m@^vccf3Ydzee4g>aw6O~>AcKcN zHDqSId=Ra$mRGF;6EadGb%JrI(^n8}xS=xCQ|!UdCeo8SUT1tVv#A#o^KhIX=c*T; z+IC`KK4BoO>=)ciivj|}w!q=Bo<6Z>`Kx!oC>;Y-E5>SHT0zI+zU=cAvENowp>bj9 ziyp>4`;F<)y(Sf zRjRRS%)*a5t6eaeKEN*@JlF%azJ)hrmp}6ztY+mF#fP|*@Axe*O42w2Ym>FCA+vFD zt-34Lb{VfP{%`(Y0{AO_4p==IcQ^dA`uiKDbQ*NM4>G!Cjwq0VUk8~Kvu;K0vhO28 z$glnTL9oj{k0=8<23-?Rhn{C|7U^{DdOB=bb!#eqr+y~XuqlUch_jIsb_9=7Oj{;@ z;eva`wg39mLYOn>JEKia(C+F;7(T92w?A4#P&z8OHulUL^W1nL<_VVO<@2cj7&Yr> zzMNIGO=jjVDWfcZD3JT$wRdJL*B37B75#Al4H#od$%KZNQKh12RGqb#++~YBo*Q_-@=jn1Vs1{OJSZ+5Aa-*`;^g9-n?gh7aX~5ukD=M-x=<7ViqJj`F(%w5zGCN2Ra?;%)lZ1 zwQuFQVtJ7Ot%`#!N#7a`xui^(@1wTsg?Ds648K@(5bQB^DbVe($VIw&#Z6%;>=Hia z$aI!wb7E=X%814Y^DFo!36CgRY^QwFGmj0b(P<;4+GK+>dgqM*V#Wr){~*;i>kvnZ z53sS7A2vvV$h>yX>aMcEO?BL6JU9%*tdMYcN+Hctn%v*%H4g)TrBU0m`c~6F96(Cw zWBOLl4)T=Ba!bBLODkpLIy|S~3qB&;%P@+;;&4u;nc?eXl+%*{BudldQ#RTAvaunh zp3wL!mvs?yX^{knCwYf-wBo;$a-l{-fnvEnWt;)SlPWbs;;%^1lZx~Ql9R=WEU8pu zxk8{Q7A+MMH-AS?c_KM&i((Te(pnt6#)WGr!L^NLtyFoE{s44O=@RsSk)pmbc_Qh% zyrn(`78o8=MmS)z4zne&MO}%uG$^f8Oa;Z8!vNup=l8zUB`&UW)h_oz|gyM2}pnH<*IqBY)$BJk6+<%#~ zT!3NIGdIdXr3TQ$~6ppMB6)R=w zA0(s;(EHU5iCKfKf3Or(tdZW<$OmH$Q?d;vdcZA&qf-iNizo=znx1-jO6`oSZkA={ zA^I|u!I>cXAd?v{a`q9IIG=|G0p^d()@2g&`bc;rAX-!7rH+|Z7034((H?3-dz5(t z19JO;eXrG~+KHLV4N50*j!zW@NU4UBk?~$%K>&NPJf}XW<*cQ(p)ChWYc1Wo_rny}jY~BKzyJL&)cYzaoetik4M_WAr!&~10r?ec z9OvCp2I(SNlYEF^m(KL5QOTdk+1EdQHu~uDDFSiOb)G_Fe9p7CjODil` z*5oT^V#|WR;pGjXfZ=Y(V5!e6Pj3A7orA8Ow|r`5uwT)4KA6Z_v7K(}7*D1b>Ep$C zOb3HKTLrW>wWf5)Ez)?gzPnHmeMh9>g!7T-F{hqD0qv}Fx^tfuE(+D2R6#Pn6~g#E z-w69Y`%^(TrNdufd|iS-7(OlSOV#U)t(51XX%y`l_;9_1wO~c?K|WSCyE2TH9$a8% z>Ke`#dvy`}L)@}ftya9C^Ul zaOrsdgrJ-{wHPR^uS3?NjpCUdk#cN?)?oGh`By9orjMR;G|h&b1yMsLP?Qv4_Z{l{ zYDY9uMQC6;|4R2A)RkqZL+5)@8rj1S4Qi#Q!>g(3%$S=r;iUcc&&(oK#noPafXzU`GO1}I>TdB;;DJ1F1itei#$#O$#(>u$=6HkPOlMe+;hfb^>*VlR z4&uEg>w~3r8WhOmjX6FT3Z7CvSf0|@2oOrgWhiLK3%F+yZ0K#c=Xiko+@xMw%K8`g zouzn8!2<$;HbEz~rINJ_v^}CygK3(f7=pZ_5;Vp3o@!K@S5)uOG?Yg>&Vq@{u5{k@ z!XA@F8bJCAHy-bdO%2^zJGmG8&fzxu}Q!7}2KJJaL3!}E*WpAoPm z{fNab_p0KT;>mqcKVUgV-+1A%!U7)+n2=8E*9xRw_cg1HJ?nyF2;V3dd&n0()+6E_ zvTsFPiz3T;O6jMZx{qUH`Og(^Y0Lxtztohr*4!|tv4A{)VPhhwt5jI3fy}$y-6JYN zqxwTx#}}UbcY)&_iG{Scoa*|R0loOwTm?+$U%6QPo^j(1&R1T73HB@X)-NR6Vd%~G0v?t8<%%b^6=@MraUiY~g4fi2))wkT| zKGn~&5|)<1S1d>{B$zl1y}UcQ5uk`py!1rc14x?u-3O$0B55aNIvAc)f1+!;fV6r? z8D%tv&g3ltq~ElF^vsVPEvTQctxHX4l}!BX!L@u7r21f;s1Q$e8nA0ws7dbi_5l3* zt)Dv4fXeF?Fuv*1yOd`3c=4cuwIV&#nr;Ix!2VMvrb+c7cK+6sj}F%=-ap7Jp_L9Qw6M-k$Oh6;OKTjs&6H zOrL2k%$se7c8 z9|wkF4lFg71)QY3+>UvSw{IVgnyTy9v2>q5%gF!WLaRvVAPgA2aSpUmeaAH}%Fdkf`Q{F~M5n3DGL0|-k zGEV@zqX+Z2Mom12Oq>~>Qedti^W!=^rBoI(Hp&^HM!WW>#k5ll(j27`<-Bz{O2s_| z5Lx5`(NxOZyc)q03)->v!)Zrz{WDPqXPJy+nth}EU3*)t9er08A0h72})T|;lXlHQ5X>;h14nMOHC;P z)68<#Kr2Db4k_>bFOP#gU%O0P+O+(}VD7ey?KX#T2@s{T@{rNk^nhU&1qdP4! z${%p}QT5U|hO;j`#^g!oBVx?uG4&J~j7~~@4pE2KlxQyrI5*s=w!q|`JC}Uxr%!-) z{Kv@#nBww2W3Ho(#Ys7rJn@_}5wK$j;UuD zE3N6Yd$9ige(~Ga*9T`_I1BXtFR{To`R~{Rx@03D*6%vKh1%eTSjUG9iA1|0lu%;% zKIX&@NygV!KXhX^O@HAhmH_Mmc2DVgfN7tdWUTYSSl`D$w`IEb3$3~VU9{_@egEp~x0!sO z`B5o1?0s2oL7cDNkMa-icaVNTv4FmBD5W^L&j*A?7yG2RuXgO4vc=LmAMaO;n^Lac z9V_d7X$VzOb$jhs<`OV{tSA$@F%@;kq#@ZM`&3EYC+VyEcR$iAWIW;*Q8wJ`n%w{S z7k@3Dlh0O^Y>$Fk>)KlE=9sLukw>TOaQ~xe>-xFGkO?)9xwyR!E|K2pz<10q&a9J6xS18oKoTNvg4H< z&}~!Zh_klC#e@>c{f+(jKG!DYH>Dtv-cNoPEa|c7Df*IPaJik9fh(sonrAh3?)hlLK)zE)xw)7&c{%nY2LGWC$dKspj8x6og!o?)zzi53S{C0F#CJ=iT9s< z;c<$?lY`ABcX&^2k|~Xd%@>K|@RiaD9eB)hO1MVf{E3;O zjMsg2o*~cIb+<@tos)5ndTpn4JV5dom!Pz@w4;~Z{Da{2J0C$~CguV#My>0onQQcZ zdLYT$gOyKYv-l%R4IsrYunpS=s;nx%Msj`eMN4bGA@n|K>>TEWl;#*(TRPWs0DwWd zQZ4dwHmF-A7AnKmtM5_zA+xB+nBOyl(d>PP7nRx(`&Reqv}Vt~x$JQ5Iv{8!2ucAJ zXf6(CCw;`wj(Kg45hHykq#1!=k}#a0OfuGJ zpY^AIP zh5Kg>J5ExbmthBzzerw>RDX|HU5dC8ls3ccFb(H|&{G@!Xf5eb(Bou1u=t(J0G>=v z{$Fz3mE>(6hh?*u!OOE>P7tEJ29IV@l(K9#ca{T=1F#wo&1FgryR0{*Etc_(<(G_w z04&Snh%8l;WoRv|TGLer3&B+115{e$X}mgxhpym6xwND&#~N2pL3lnxk5C}!J>_Ws zAjEU(QWH_GPdX9Pn#3Evb%%HkHKbMxnI`zB>L8y#Rf1)DkAi3EZIE)0`aGw;r>BSl z>l~g_M^j8PXWtd2cuuKf0u4-W_}1?o0d31q=a|e;c(n@{Z5mKo;?> zij|Xq$yv$iST^P0`OPj&6wGVAQ z@U8onz=Os%LEXnke)aX+#h-5^JfxKRX{a-}u_u;CZ*0yt^(3-2Ikxo0P6Au{2I_i& zp^D0VEL|?-Ep?vAVG_w@Xl-GwX;XvJ(1+o?nEk1Czj?BueadV3X5hx~)5>z=nr4{4v#V(Two7z=hF%z-|W19y2nDUXA-+z-p(6rZR= zC@NDz_nR2r^vUDFV-roq)zn9FJpS!6 zD^hEFn;+m_UncpaEUrG!Ddk>89#af*86O;;Q|{GWJBCs1(W#-?K+1uIO-md1=slGo zrWOVs8F1c2C?HJwVh$Y@W;zQtyxsbxYtKD)-%C96a79|#$I6w{8+LuQNoM(qr(sQ( zOYyR?XTa=FnJ~5jjQi4w6dLo!vZi54y0`>EqMmrpG@&WQWqhhRMzZ7XNgbJ-zLY)$ z17l7Fj*ws|w+)nGw80dYdoaX9$hkM0bhvrk=ebA7E!k|)FJuW4%iyUMkoS_wwh`jV z_4!1RnrO)r&%>lw@0i5FYmucJ3-D;_xY{lCg2#HTYwF~;wJSaL1G_bc_Ct|QC?GxwAFiDHjSSW0%D+>0Y__J``@tP75Tn=ZXeSmdL1 zeovp`e~k%GYTTY}wk6$+1~sVO-zT3p!`rvPYd{;Gx|=urR}(-gmf(}TOzdN@=k9yM znl&$rduvv|YSL4hfP_LGSxD_q9!rfx``WcVl=fZGv{4ppf~N9`5PMaF}pvJK#Pqz0SLT~C88 zt7n7nn#Oo@;g(K^`->DL9hWmQG*fPuc3X}n1!qNy2a{+HwUBVk3#&Hc_XF ze6CWRbd%7ModO0)RgBDWhehl?(=$ z{_<<{;fxDs5zVly1IAfRoYRV|H%$vlgIb21pcQxbT)jAN(o|zk<=)Lw2IA5I0?{eE z?*(fSh$eXMxiv3mzC>$E|M{R3Tq{Nu9)9>Sc*8+ch4vJ~st#^;j&JIfv(9myk+Yec z<&~;HJ7#&1lZ9%wlof4*kVkddh9PtHzJfd}0javE0RdQg9hcJ0?^?{cXN^&OgOGBi zpq#D-njvF!UgI*lP~OhulFqtS$v}riwkyXc}D9xByS!2rj9G|*X@sVmPc22D3 zxx-5;+cSbVZOzV=!5<^>S#lp`p3IAF{k!%7Ox$&Mxa0Tt!rR{T5pn(4BM-6@IN>eH zdUd*K_Lbt^&O1*u_4B8PmYVZv2|z_~3JErSzAJ{Vu8Qif*81MGDr#}hoQkwYW2U_N zZ~>(*iQ!b`uCZe~d3S0HN+|yVE>DNpNBy%P%}S0%e*XZ6Z8rk!&31w@ov(nk&%K;_ zY}KmeaM1q8!s`w=-ozV7{=*httyZB@sfb^Cyz#Vi;We*13Xbf4C#+k$5f0g9Z*cAQ zm;k~)3$hV(0V_g}bi>@4b*`kv608Iynl^f3-Vq-BN-KC# z%W>!tdq|cw#_z zoAR|0c_y+}>>lT*$z#O4`w?vJb^FhrYz$OZ^uS*q`5WxE(;@KAw_PY?Xh@EBbaaRV z&(A*NgYd@F&xOOLoes}Ew<=X{2vAo)yFnZ~_TqcFcz<7i9OfyFY#uFlDG>hB$l*DS zR6l*or%n*>yZPJmP1y~FR-1O@YO5A3^f~YO$>IR~3b8D7~xfD-|$CESWEdNsOPGBwNjOlts>gm@`ISOVS_pi=uO`rRk($3D#!pDC5 z&V++^+#{vY-P9A;E?>wqA$dS^m)1o3fw)b}P+HoDl%e5fz%%n5 z&?}L6?rT%^`I)DF0A?I|T1tERr-zon0o&~c+q}#@U#zx1S*ncruE_QFgLnL=B-Ov^ zTXXB~$gQ}nAGON>arf1WhID-CR|-nhPX2S!LDsF^;P~amW%>j6J0`V+pgRQ~zNWM& zAk`i5z^Ny}>v!Hu?5C*U;1<(Z4DGGB+xHPqk_wVD6C^WL!U-bXuNGXz4ZywuO& z-@ZKdfhw+IA~+2JQ{1<@-NwjN2Cs)sGIf{dcVynWz;jfC(nc%1p7=+-XWHNdM}QBo zS^*fpK8Dxtw3h&+bb_;b<#IUjxObb5pl4zJtj_F3P5!H;Deda&3SNKx0jI$!Gd~Cu z`&}O#8?%5Zuhn1V#Voq4l=S4mZdQP1t@Qs>hSm=#tT|-y1#?dx^I$)<-Hd0-yXF*J zWiJ?(I;KnwoH94iC2nF7@3k|ot;`{t=hS&1#hGmwI|+X$;qU}d7Vh*qvFcZj!gtuP z1rFYEPnf#T@j>wED{Vp=Qy;+k;FSKI1x!~x`!ejD+p~YPtfrI-fxE6+7@UMS^PC`!6wd%+9LB#C!`LyefOYFOII8wl z2uP3r*Pv$9??@p{X%_gbb(}uyLjstBvaoaqi!>1{_l5^=3^SKBr>ip~4hc$!R*|=$ zylH)}P9=f<*7-P#mh{5HCB3P=ZJejDgUcal1erRI$$d(ath=DcA6bT0ZbFsfzT#{f>o`PIymh z=9SekLYmU7nV%16L(hpkkqmF@UboY$;NbmFapWnL zjiK|rXZ>w;J|NZ0_;?+Evw-OiJr(GvMvel=@qa*Ut&4KmCFeMZCG+zmxE} zwqIY4TD^dGU9})}%`qgXwV{~Y?~i2z*E7>T`k3*CHwy*;x!GENT6CqBE@*9%R=OEr{*{X|s)QA)!cr^Jg1S=P4)xJ^ z7~d65Q?aXxwJOzN?_Bnpp<1< zigS1DX8wK0>XkY7tC1wDA2-IevR}1wg#n_v5&QgT`0IBPXZb#3PpJl^_)E|IwDj|D zd*i1Z7pW{%NN+H3@hWo+wz5HM0HQJ=^cSVLDp#@xTR*&MzmK2f^eLT0;1eEF-%^>8 zF(<@R3YJNT0%_VoLw?>5TRHhqg zU@YhmT|QLG`6)R;rIkHi+jEb-gTONnjAm(0wU*T1Q%Vn%;V94X-5Q|k-y>(7<{|Dad9S578rM}oV;E$%kXH^N z{^@l%`Gog4v#Ssw4FO2sqf?%xeO_myoeR&=BA@1eQx8v<&6&bx^LU`60l&5uE!mQ; zJ?*iA0N+`A9bL+VGPIctUfSWoceghfv=q#%JD4JH=D#{{5xPj&7=2 zE47|mPdVeV7x}={QGBL(N3e~t`AR8Szj?MIlG&}l0@Dw9 zlOx}Aq9`!c$8&2}rL?6RdtDAy=74)$Rt3f*0{Ek}g98lne{fey zD!0p0eoHUk-}&POgPK`pVOI3kgv<6ctX#FinN5ZGNV8^jzNWO6kyF<4zTX*-J>p%k zb1%1oE~|X?)P;YgAvdk1{3}D701-wfhjQ{My|3l>lOmgKLLTXwZ}pzH=(|Qsne65c zmf5O2qWs)}+`XVZ{n6`hyztn7D5cv=vRkRw8d|(il>EVT$Y{4Rug_w>HG$YQuD0+@*m5@3t!!*EJTFxUqe4 zK>6*{mC-%93&xF!gvT|z&vYp3&>9_<^Onr1CFO>L3XJ-IWT9X^z~C|G{!C>~xp zP=TWldq-*YLGD=tGrn;yf9q(& zMI|V$>m$_sAa$AaraREK8vtHd=kk$KKsq*-=ORR zAsJ~0Ztjs(r#MHs%Oh&qq{9wDD9O|dWI8cvgWO4vQkS__>N>9cdqa<8s*tX;xuYcw zX*=m2(L5QM2Sh24I0dA7sh-Moy_Ao~+s^(-s;+n2b$8qdYpv?RG7=aod~VBY7!bf^ z(>UcL$ER9QJ84X-?Jy*8o-=#n-b{uVtJC|aC4J%f4dy;-NwWZH9x$biU#nep$JL#I z?$@D>Qu4V;J~Vs|f0@}xZR0r{XWXTdF@q4xCcsyj$|S&--ko}(8~4hQ!Hp6mx3BGB zeQlJDvb0*ov-q%-qrgiZAG4$FWH|SXDJ}T8bwjlf<6L*p*dW zEybh3QjBs+^OMFzMj>~nbh)W`O0$*@vMl{HD8+`zmB7N;T^=Zn zwG;8?qyS`0wXfPEk=6eH=395z$q^64SNVxaeq6;NR}(c^ z-&Bi9sha5i&Md|WEi3go9vDx{%&fS6IzG0*_!^joCVt!Cit1QTgRIazQt5}qAXm9N@C%~@@ zwJ1;G))7lht}ETDvU-?+z*cyTpJeC6(}69!QS_;!k9srQbMLRAYvLKu^X$#ixIy># zr5rp%5`c20qP_H?kjEsW+k+!lG=FKpN}lkSIdPeuIH~8j zwchbq1+@_2DcU29A1S65ofgL3)N9Z6zacM6z9oD}A%(IJpVRVE%W9OBA%%}GGyQW4 zLiMjs7x$L#ywgMv8_0i{kh_-7P5g4^v23_Z2%NFDUjS&@J*Bmlr|zPb_beMzrEU}I z72Q#V`%Z$m^wK?@wfS083P?{qHBJC2YAE+0$4<$COMBZv%odATXvha|){)g=>Gd;D zIX_kCYkswqP*kvdaH@W1o!cF*C!ai@l7JT&M$1r!(b^D(iWUm{!oBzW#>n}5?!5t~ zPw9fbRkPF9$;tnHt7j7eai6D@@J14zQipteNVrN{xe>G%@xI{zjoh|@yqYW`peTz+ zllk#1h>~#xC%)w5bhL}$JxAk5mI4WE-lC{tI6ZMcX^7RvKhOHxmxq)DKO{f>I28E$ zAlTnFKm+b8#WMEy$EJLds_!Vusb@^naGgeNEfShaQ#z=9QgXtU(bYpYnWJgQP=q^x zH1tawIXV(enrm|4jB1>k3-l|EDU;_)Q<^1I{Jk+$OB&jHs%MJUX@D%`&dG7pFCGIV z^5{v9cfWl~##k6ugR)f3gt#nV6s&TOk|not>s#w-pXvw;6(=crR;yNdB7EdNJ=|+1 zmg<>(6=S|vCT8}2GoMN)<@6$)-OqjNFzBB8*79?=Qo;0_og$>PtBS_np1s9@Hsv?#=^vjonlk-nl(&aS4;UZm=5PR zQfK3N4rrxdRPUden8?JH9rBq6Z+YCvKs*rA&be+0Y)*bRAwYfWasWkj+Zc9Cy%|6hPn^+lwZ5%HjDlM{QTEZ+SO1{^2AM_wF@iD{I$q(b3!27?@q( zd>1|53y;U(xF7|`IVcCmAEM{Q`YoTF>FRufilA`g6&gY&U3Q*%%6XYeAL?-_Yx&;S z7SpAB{S1|r8h~oROPBqrLP-Bj@6mvqrSPipP_1yMb<#N|a|Zxd4WvN%$saxz=6>%^ zxMKcQaQ-PDC^e-`2QxEf4adH3MzE0<4V6TY^bf>oNb6a=XMs~ZX3g57w4-8f1uwh+ zAdUB8g7}gPuX+%+g}sNoZhlG5JA|t@P!^H0)1du4ipdGdar3X10zz*jzB=z;_D=!Q z`ByH2lg^!9SX`9ysFdezUyr0C7(nV==R?iRdqxYY<8Ssa5)fF@RR+=%6*FJ|NZiblMu6>c2H8)$j5(rhb^%AHj%+DRPIx^)20J`1d`&y==P{bKH}y7sRkXXn0cYE42?9vTyQ z^R}0E7wkh*1&ycDs0IFL`IN^V)G79hNqa-Cj677|akxf#ialiHnrJIq;I|jRtT$;+ z83Y}JaF3;0uts=>K@I_-mal@#40P+KbZ3lM=!>)D(VcsEO2I=pLjC1?Upb}oVz#h> z+sCxllWIt_wrL&i>;@qlq!US@eob=?TcC~g3}OP2-kpa1eHc=5#-hvw5a z$+CabfYQ8~NxmkOXZFnOSzq9u`j#tKu1IN0Yi)>@VV#0|6I8YLD?qwQ{B8_b(GNK$ z-Mkqp2t-$|1fINaK=G&bd&ht}wq!t1u@i>#00ArqD|Snj&2WpK5>Jnw8sP+x+H6P) z9wX2_KnkAKZ+m^&vh|L1y>rqQDKHXyGh=Hvpm{iB#bYYCH)H)QCp@JxRfhL*4|Nn1 ziYUc%ic8utSDdG@$wWwwh765@bdaPBR{nx1i;hpX!_|6Uh#Nc~uPAUCNnTcgZH4AG zR(oBgvw=v|C0>gZ7qR7WZP!q3*M6vN48j@-+EF=dzr%Q|EoBhoHcMG4k_Iiq3m}*5 zF`W+ejy?tbw!o9aQ0%?2q4)RO4ywQ>UO}TLy|?s(Z=Y)R6iL!$SxG0JGtJIML!e*t zn|cNuWf($XJX%=chb2EFOAFQ5+j(l@EQBEE)~7XhH5hs#%yAcVOfy*v=51?5RK-i~4=F1Yzydwg2e!HrxEafqBFnK)9MXupEQy$Xz;^VZ3BAn-6H4{ujbS0M8% zx3vcCQDxQNO4_DTo9&^?n5N0G{E$qEW!DWb3lr6qVN^7pHdyvoeyN$)1Rb7JNi-^` z&Cp#gBQ%P?`SzV~)&<89iyljDCV-q$T2SkJY6YYXs;;?`uDX4k?$2va}bwmgg+He?X8c-Sn zX$50?s58W+!c%Zd|J&8!wu;>*?w;9bvp}gnfB50OQhcL+I(}L8-=WTy*NHIv?3Z67 z*1ZhYdtme<@0hBV3wTbw+4^xvvlt=S92JZ4p>bQHQoD0v-(r5CwTFhq`q~_HRz(D8Pywo}6oKCJ)N}EKE?#BNNq@ zYFU@(%_&cg=iw3z2fuC#Jhb*{wek_CI9Y{%C$XfTfb7WL7r+=m0cN}=^Lg0x6ARTv z2}(yHP_18B06-QUixLb2YM;#V6;Hy1aXSY=VXe-Rx7452iHf8-n7TRZ%zcHM(MS(4 zKF|f~-GiA;=xB8xu0dZ*N>12_4!fgEv(cv87}}=TwS+t!S4=-9S|YS^q9C?bdPM+hNTI`&H!H*5svQP^v?|dPQoYTMQIAik5hj}4 z51#b?wv!u8;X0tv8A7h-qFSB0!iFSo!#&Hv&hnSPEXgf(p&T(D#-cUS8R_A^)DMk@ zO5&|w#GG*PrAGv}v^dx^)FXpCV0hUe%W@5u#0}1inBzSxt;%@Ir)C;d%cx60U_oUC zC(n!@8(9x#0a-RuI3uJ`@~``r_u#qdPFEEJrxKYR3G^}d`**gjSZX_eR-3mJZ{U?^ z2zlRvR<-rT4|$acrLBLr-(jrNQ^t2i^$(R94^5xknfu7F3?n7-Z279?4L`_7HuF3q z8-;jE%LZPC(bRK!##=HPH>aI|=OmeyjoR2LBm)O4PeaerYemz_TeV!ZdIeM?4qN*A z3v_j!s)I5#0VplHRP8quO`M-S=<~u2VO7kVyuL|?;)BxyPhxIB(2S}4eu;bj=< zR^KA;;yD+%rEM}YNVQdJMb9<0Sq#Q%TqmXD$ot%-Jaeqj?R{&JE?Kdly;dQa(Kw2s`L?FAbn zh-K?P-e{MDKX*2R2IP9Mz*j!nL%( zFT+T*_8`zhu2D41;Y`p&2`1PfI3_Hv#g{BJj4+H{~auR&04=}ni+OTjJ9^)?PlRGK{_ef=A!C{kYz+in2I z*y-3K-zKc*(JKW0BIVQj-uEuJ_Szeg_jIN@gby02uU&mEIw&Fa^~GT5}G z0t5X6V#2oV{=36Zulp*z=bfK5a?zKWA)Znnh=ycj2xJynrS#wN<7>VGJMS#_lumr* zHn37T7SIZ>Sb=Wq(Mgs)CY}%xh-2MCB%KdHmhn`L&??}y>GqW7S+>{uK+LxghpfNT z+KrXfSdi%JaP9S%WG)~0fHCxUt?Tt3$W^M(fBe5+R7>|d_YB65iE0!#z|ESR%)erh zbDeosnlaOx6Ss?EoJ#u(j(GmQDH ziN1~R#$gUuC#6P1EBp|!^j8Us%GNBPnw55*pL@Kn0qMc7n+&Tv049uy4E2?z%JRyF z6j(r53RK-NVy%zi;%okU(DEBr(^{%THf^Ty!jGb~gsu{HcB=?aTN(baC zrL(E`zyIBE_0`wb>?nC)lK$;qFA`TDe|+vKuY5cOIvL?YWX^Rv&}32OPoL81eGAsQ z19T~COPI5DMlr((#V8&;mu>5+kX}W6ZQ!%3Vr< zEF)f>Bv7*&S$kNiEciNAr&zxHA3GmC(|ZP}Tw;@)1@Y*a|l?>t%e@ zmS*i=$QU7cwSxx>pmHsN5!(kcuKK&d)M{f+xd{pNbpWp@VvEamtllP~6O z0T`D6ylSOl!0M__fOo#_YTc3R$FdDWLqSy4-h8Sm_@ zT18fhpO~fiNd0?x%Aj^Kc4}Hs8k#Zq%lJ2bYp%F{_tguBWRTE2pUYP~Wv+efV;_X? zeCLWx0IESHy{18?4>alDd0>^s*U#avFm94Q3`M{V)Z@ksZDXeVq%DmVOIoPo; zjKS3|hwKag`-`upWF(cXzOu)cvHr9Ap06eKuZ5QLsg`tAC5Dbl1|KUi_R8(7!r*BD zZoXu`xbo$neXWpIv=x@?n--L2?HkQ<52pV<=DpK{jbKwRui0(0xJ=h{g3y-Ez4ZY& z`Sin5Gpnqnc^{Z&X+kN`^v|>I{pgyD#r6VSDqQ}+8E598!!yPtb>X)^ctHG~bZ&RC z0gacUWLO0;FNJ#ZenOt+Ddho%j53U3Fx$Es)_p40%3iltPFP&H$FYe|#Ds%XKYZ(V z?=G-*<#|DtDT(v@! zv7^cikE>xD;NH36E0wjju}9sHb$!@xaL$SU9>hOB2yI0T>WG8Vp{Ue6zxrlxb`V?|9`LjdQeN61w2EYNFRNDeTA;kG;km3A6EU{ z$*;q8#;pM4L@aV1o*DBj!hKJyQljJb6MZFWXePbasQX%qblkeB;Ds!H%XU|W;b{NJ zvuWETSq0>=;S!Y?OLB}(n^cw0se8y%N;Qin4Z?4#52MsE&&X?II?=0Q#aw@GYy@As z%LaN4U;VsQI> zOn6M^eE$KW4V7G_f~AvF&rq@B*$D{GXIBRoz*Jv0iX<-iDi3|_jxI_@^V_22ow2hnB ziUv0K_Wup;Ck+A3P>0f;ChMSSTzU29;0yo#@5%dJKq~ikEaf+s&N8L*NN`)+uMGU2~4wqsQx?D!TdOQ{OFo5z#pG`8rF2#9BDv0 zUI9{IKImj#M@my>QH#J+&YR(YbH~8R8DyYg0lM{Rp-KVQ{8I(qV(*Xaq>)*+Qrb@& z&KYk+1`XDs~O#S2f8-FMO>8`s?fIq+Ztl?xGKehs0T~+gU zq&P+m|0v0;D4RNZ`V^-tQ#ATXJ>@%T1!(J0;^hEYWdK#+tDoY zcNSC@K6LX^sU=0~3S!y5QUTK)cANln=3Na}Ty=43nZRGFr$E%#if-AmC3x-XpM6OH zQa@j~WMaHFF)!mR4aR|BNqT$U4;MMlWh;}ZAa&C%!^n%c(gJ^Ue?-bt%E$zddVndl zh-FV7Ihh+dT1|6+ONg%lsV{S7+m7J$4AYBQnJ)vneW_p*En;hg97@FvS_n^&?%)%dP| zx_KGA?ySkmNf?;U!a0MDNgAjzUA^Wh*tHK}zx^h|c)81MClGo{+h?vc3TFr^l2C~D0O4`=~`qEX%Ya;!^#U@Lsm1oybsdb--1VbQZnK< zm)rqw`P59%l!Zoud2OA8yKR7KMx@e(!G=vB=%V6yK*(O?4!`)P7r{*n0-=dz#qH@yeYX5!^deP%0x#sklf>wxE9 zSOE`R_gUC!b1VSr@kjk@3YdmmdTX%y$dY-mdd*6)6>d57iI-Or;frrTF4E2p35HYo z%k1CzpA(I|=6v_AAb!cCzzhM=R?(JLM|%ddw5VAhD)d1$;QQ5AZx+wo`Qrs}-1}yj z?u5}f&*<}kJ}72)0UluNESq~>z`C+J04rDj1D5~lzlG`^0je{13bZ2xqUg3vWU0fx zLobuWsy=Z00FSeT7|$$&7(O_2?Cx(LN5U=Nxfibg=I`LmpPZ@Mwr72=4zqGVc|L*gn=0$}ah(hX;z+DeqHIUa zDatJgFacI4a`V||{|3)o`$hQcU;YlWW*wW2G1NZ@Mpq-fQ&j?07?3Jmd|#Et&{3^A zJgW|&z6J(B?h$fV{99;AwNi~sDy`doc(=H=eED*rCCyqbZ6(mz^q{opvVPX=!Uw0Q zBHw-Y-QkV|nBp=%Z9AwfoiL_CW_~jK>E@+y@EMc5nI2E;I5<)<$&KDf&QHN0?m1=2 ztZ3z$CuPIK&c`Juo2I~!8vo>87m-ZF1vWm5K5N~Og-<) z#o=W~EC+(3S<d;x+itO1CRC_z;@OJ$G}aO z-UYu-fax1AJVx?$a!IEYDY~R26%}9cdurLpFdvb)FJzbDGK~dCD6$~-_V+8fsufw1 zXLSYZgB=gr3;y`rQ$j8aRRU^9V_dqA1>F>07j8|fN&Fa`vLX0Q9)W6=86Hutct?di zR!Sng$CM(7a<77t={=hVewzub%`XN;%WnrvWZy@C!x2sV)Kj+|MQuj=I$Y-*V-X86?uNvhbck}MFHy1zw~Pp_nxa4rN$$n<;=@R#(C($ z@m&?M?-LK7W-85t>XJ3#b^tsu?zk~gu^h4deEIvY=V>kJxzn6D(r-crlca`wk1Fumow_j-0fgsW78M`E4tuvD1)`o;Phg9&3KRnvqqk>UKMR`B4Y zP2?@EK#r*hyOIfGBcObukjFtvsoa2h&k!uZEI`I>2JtXsiz!!l3II6OPCg)1xUN8M9ihrPhVnN3#XPcuiY>IJQat-bS2P z)irrfg4l|Ezj_CY-1MS|yw`i5^L%9EQ?MB+F4H;Rm7Jvi`J;<-m+XreJLMTUHLG@Y z)M-iwvsWTZ^_{nbkH?cwJ}KhdjoMO5511UeM5=@l&Cf+c`I2lT+mn^;D?y&jKr=oH_A*vAn65 z`;uM!d-Emp#QA9-I{|+1@v8&|5t>2rtLu}Vw_B*TNvFxoA& zrFSR56hSJ6si#aO*731eW(T6S*HjU5<8>CY1lNL{4dq;Ua53jzE;Xd5e(11N5{@fT zC``3hYF=6r{Ecvyn;q*9My2b~t+ieywKBz1E3q1Qdr&zlD_(-tk4M?%=J`#3`lK#c z{6xRQ?yae!ZvM_aaQ4TKOI0DSt1I!`&*I8xUdPwtf}p?XtC6D00qZK*7(0zhL#HBpNQ>^n&>vsN(SVeK)1Q3qIsr^Epw=`*`?;|% z30|m^WDy0s*7Dq1%KHyF<7G}kL{yVl=!c_fsA+S+}$$&U(|x&JoOJL0OH_A)%Bl$TVu zZ--+v`44HLj5WS`hjv4X9-pj5J2|Aw9ctJx*&8WhcZ>%8x$>|H|3_O(E0EsWI6;5BN-Oy_;5 z5FicBN)U`{aEiZIfA$w9ox6}K%5o){7O48cc-NsD37QQ zTDij!N{0Y9eKJ@eAiYuoQrtsI2N67^hLi`Vr#>62;ZX$c@=T3#5ztH;-4fG{?)v3J zlnG65Lj@QoLb7aSWe*(MJQlaYk3EW}SdqQ&vd<&1cH(Pb&Cah*c_H zk0+i_+qY_;Q!9}gm?DSi_20bRrp03d7^ycV&68^RN@IPW4><9;c^4O+m}EYz%h8z7 zIO+H%Z!x#|h-rN8#D95nKWx~X+#8T-4R9MDt?YmMy*ott9)J9CMY`1#9)iZZl5KZ z8Ysk5TK1t5%x=Y!aBmfi@Nr5G(m2iC>0Kk*85K|7ml{*M6AxF(~0Js0}9#f`e%a$3x_E}5z zMF46&8q;PCqjpbemV42>XQ%;G2$<>ysP~iVU;jX0I(6z)k=DIGSqw-1+o9I|nFmg} z*l+4vz85H8&Jb3613FD4JEeJw@(II<%3G63f=e#anCm?-H2s3?0yW0qsk=+prT=rw z_NBZkL)(S@-d4FCy+icTMoY57EpMys0|9PJvhjg4r_8t(~Ll7}}T#gWw?LB$moQ(mt8G&DzLq^5|vH z<7?IB%jzm0IOE0QL$3GWH}Bs77hiB+-R)*;wa3w%=4eZ6sPfZjI*r8t!X<}`e)5^4 zwkt4mtdGu49NM_a7e=Gr=WDZo#L~DbFHTkpnr9UJwkg`Im8TF%(5E>$Wk6~qwT4G2 zmlXGDq~gz*G6ohb=`mDFk-CpYPY6sg%=y9naK=ZDl-!>YGw!t`l&j+XV5pq5o6$HD z%&5jd$xR=GJ5;2H5-wA9`69)ws?tZfjRwszSSqSWxerHYOn8q+7L-e18Nuw!ZWr%7 z>HK5iTjzZbzJKA5Q()9TeDImKTwj#4y#%Er1XQy$rSum+x~71lpc5MjJ*VmDb8Jw5 z{_~&Vzyl8yf8X7;qqf$J{o-#QVZWzX z0+Cs={*$?yXyEsjOC)mhyWRVvdG4Z0WPmhRK9@1!4*`y~JJUWKF|8~@b6()pu4oH0}?meg7>6){6trncV8_v zC)X+&@pbwbKdMNQ^0P`mXX{Dh+|I~bdtG=e=N2cxR_*_lQ^uTY^A29ni zMSOi<^>LBDT9T9Zt1^EeeP?6(bz;rJxPW@3(YhH%T_O&PfN5pzV+qz9$&%*pMBqk& zX^Mi0TQ5ltJ(L1#+-Oy)M%6xxvS{(LKFc#Iq^opEI*{~V)R?08Ck$`-)J!FP;#6AZ zQ1Q9oP343RN~e$Gd@O0D4Cj>f#3aT+98-`dm2t7Z5rJs6isLKTvP7DiN`lonL_2!g zM`sE^T1_HRKpN7LHezw#sv6U#HgpOB(!5!Rzn8<`Q|cessPK5?kw=7<6a(%vz3Zw4 zZU+tMO60!N*jnwgeBVdRe<*JWk2x_!z(C=vbF!lhesH9ag(QxhueRwdA9 z+3#k)f|+Fwuzor$^Beqs_Ri;3mZOT}U32e41Xpg{xNzYgU<~>KlH?_bi9wAZhzUW( z7%)GHkbny#0Zo($5u=glCINTuG`y%p2x?G6B$%xm5l!5=5OrbRbbG72PxYzOr+)NI z&z=79{U-O#kDjXTp6Rao)H!ud1?tgeG#JIKTofL_`(-0pWKCp0%C8bU*4{Dr-+?KN zQp&{7vk27LJ027G>P&K9e6ZD9g)Cu+^agrHTfSF6CnFb}5T1zc9Cy30a~3Q1mOkXa z^d9#T=9SJBW+&CldjI*0%X9$9^MAU&x9}m+GiaE?Pbkma;znHj_TNuDaGg7%pFHs* zON1}hwKo+z&aU043em18<#_^sYK;DS)^A%FZH!II5~mEzfByZK>esh^`KIFa*IzHb zdDnLwfD)MU7#8WWPr2~d1fEiomH&R!= zVwT8mJ1?*8Uv8%f>jhaVz52^8!ntiId-a!HhJtztx!RJ-%8UBD@|725N{!t~TfXx4 z-~ zXNhH&RBNdwOCni%?e^Av=f0n__qQckb7gt5RF>`b+M8BesZZMLw`38oc02txwIw@R z{-inlvWwQOihg-l|F*HT)>d{q7&Wo-C++=JbdkWVCD)d(Ev>bMr7OQJn*=oVZ+B|z z-?aC3`~BPVYpwisd1uKji}#+Gyuq3}2 z-Ig$h^f&$at+MtslvU?tI6b>QX+GC>+w`5b9jUz(XYfUVJg%Q*HJ-!R4r>&Q!X&Zmmy6H(Dd*H*x<6nHzfv7ZaX{jisp^Us`LzWj^BBag&N;NRm z-0fP>l7v!vP9VykYY@sIl`eGqclFg*_l~ifb4tTBKfMbimVQ+kui4TzfZWFxR0M^XRA^xMetzWcg?#-`yV z_qbPoTb??W#(iEn_qi>5!rkYt{_eNkY&!RSl~KN#9?*V&b)(*vFXeVwzHz^I&`<9B zaCv`wmwraN|2-&`<;nf8l(!wH2|=wLkes&rZ_B^yElvymWEqnMrp@-x-FEwdpmaIl zwq%&S`bW>{>wAm6h6rTD}y4`jIVh)`&HD}wlFLnK= z8wRyS3#ILVcGH!&vjr}H_gB3`zxm!9f>2EN78wNS-rrs+8>nu#pKeZE+u@*_p!ULP zarvqKeqVj{Rp(XZ04iU{=9FqFEK|WvONP?fuIQxAEsd_t%jTAbtgk1oL+}6C^1^xT zwb$y4_Mso#U;O&n#%*rrocfS@jUOe%R&1fnFNMehYS?@9?{A-bwRc>X?!3lJt3geU zcV4|js)ikd%s^_~F&WeCzn7~XZx!Ck=*z078>ZH!YZOZ_Wj$r#~t9Cf~QL9 zzAe+1_frH>{oe6$3wphoj<4wiT#6EwZ?>w8E6)=}^Srt=z$i-g>r?$z_XW~e!sV+q zEO~ZSD0y`0JtF?XOZ!sE@@2PB1X;S9<7x)JjEDKW%sO-N~R}@15Gi*o^LPx$njrh%I!!_`@a$ z_7_jT-+WAC%=rr5S~RVgQ`{W)HI<~P0X)2>_p zwL2c~!Kn5Z0@B!GKPgu|qVH!2sUcH0fhmu|rw$?nq*^4uwVKlNC+~Z@c;%H>>UzKO zqX+9orGwNz?0rtYHS~kb64-$akw2;k?&q0;yX^aMz^^;ebN)brf0RRGF4S)J3ycT# zl~^!=4HPPUCA^A3v0)20R3eEj1>W`2&UVK8=KSO$2u2*g^8L`g;`UJW2P}b}>)=%b(gmIs?Wph*I0$TFI=zAW& ze)PQ`ASv8^LtRLIEnberO8C@pVU-&WzwP_9<>*d4{If1*#WO(T$g^<)i53_BG*x!SmB2>v&eSUe!ZAo+j`` zn+}GJyhfCJ%S4W&7Za!C7dGL`DC12fKL&1Hd^2^*C|=(5cFS{u8lyBIM8fVf1q*;Qg*Vz_ZnTfycSGwXYAnIO+yhK+y8BXH z$5(IvM$H9e8I{&g>8_XaMJ1euqV9K%wqGKo&Sp+2w`zvoiv>N&;3q!6l+P{Ylcaed zRP0aAQPp1CdLMoK-tHo@_tm@KQJBB~TkpLpw{QFA6vZhkt|Bp4%gvtAX3i zbkE$(?zcVv-}R5b`)l#S3*W0>>T^oR_$D#0bi8uo@9X{7eBeB9=_B4#CXuzm-}uh= zy{Gu+pZ?;u*#Y#oAA3&BA2&f)yamzNb`40mmDEa`L#las*OV4&)_F?hd)lKEx$wF5 zlUq*7VoKIfX(iRn@ibSJL#VBTgRXu4^+%owf^rP1V^AIn_=>@Ns?J>p2Sa{CXdU0f zRL*hg-*sppO>KkB9wG<8GH{dr)@KczyT+fM@Zdd=25dQx zy`Z8``3vf3QSqT%qXeTIV)QD$y`Fo)(0TM(*k14oJLFrf>C_o734Y1w+9!g~o;a(lvo=5MqP zN9Q=_3QOyhA=pA`$W1&1ic8z_Ql5>N+g@5q zd3!@`lFbT2$7!F(0ym-cK(K^T2}Ba$j&+Zu%I3gp2=aIa9tnr^87(?qvwF%^nNse0 zZ9lm{y2ie85qV1G52%4<3{0uf=a5PkQh5P!@Z>K06p-e)?L#m+)FOIF*c_uiKq(*) z=T!uOG-NI1)=>_pnl)(neL6R5CtUcs;!qm1nC9GX{QWWemYn-LXYOgPJ3nT^G>>?tRUpqGbl*17_JF+t1m^;AO)l;CU#N#!?YY-AXqksr=A+r4mv@!AU9ie9RiH z1y#dBx@kiVM<;*Qvjn~Qy;}5^kegAL+<<#bjIK{Wr^O`WxtkobP<70 zV}Yr0Yi@V*OyyJn>LlcaD6OJ7(e@!1zSd!#7mxxV0B!iL4-cXmjA|BBp7WST*=zFx z*9Vqx;pZskzRw91n!-Jn3u-aI9vb)*bL;0O!B4GY496n{7BfqbPwQx z@OzI7q7oi8n3Pk4xRo^2*~an|11?u}m3hAdUvVfF{k;!3?c3+<3#6fYLY`Obc_^P~ zE|A9R4Z$*ibm36CFPLg&Vt?Ff$~zbir2FI}onksCz!f@OTm$=c%sI;;b1)_MeW)YU z>g8?BEw|k7mKufj1?c&Kw`M5~S@_0k@6OYO9|F+WwiG<(y7qH|ssN-bhte^?G*&)j zH4Rxp<=oU%8mJJULI53TCb*M;QQp49fK;v)C$oRZx^n|3rwLt4hs5K}f7MnV8VXT! zX{&}TL#hF23R2~&Sh3Hi;21!nEqB*JMpp|y=r>71~$xsqk1Xr7;4zK1V@~evb-3{DwV|bi zI`q8KW48}E$@OE~Qql9d*3luUwqOKUIF#-RttofD2Bxxe(cm-n2oQy!btsmjR4yM% z7Sd3M6`P~Fe6XC;@gB#8FPFuP1?emWNJGb(T81=cIUVu{AO(~rf9P0VPHrL1g;)(n zwf9mGnqw`6H41{}2b{6@wSg#Q@E{NBAPv12 z1J+piP(A2#0i}a3V9gTBpXUOrd`v-UZYQ?n0RsfB9ZseDKDLCi%~2|s5v8)^#gG(Zg%gi&7C%D&kGR#yFcu^`H=rCKDp2BmXrJ9h=aApklA zM2DoXf>sEnLoaU4O|NZB)uCBhht44dm;#`obwQ~GQVS9x>lJ-Yg6VirI=9qNP)HI; zQ@J+h+7|5tj5*U60HlD@gI~C@hC5^_O}!4)k@`Hq6M~ij@417_oXj0^ZE_A8+GmFeQe+v{t>D&)S;g|ayVRSskhg>rx>p!6UYYN`W?SxQ5Y8-v!+K68!* zf}r_Bb7Yr7R!u`gU~ouK(ij0u096QDc3Tr$%9wJM+UK;~sC}g8c5W%Xw$JG`f4uhE zYbOJj=$H?$H{X2It#_~GC*?4z%`06ZfF9zr2xbD5P7YLenF|Uag&?#m^gL!QB_Jgz zB{1bs%3n(`5DqrE_Z2#;_!(Rtb{8$ib8>of1gxcD{6I$SNv< zR9*|(ajkV=G3Ifh-v*SP%Y~YgN-6}HxJV%gN(DI*7;pgPb4n?xK7nVd9u6S(k1V59 z2e-sh{oG<20?}hyOQ#45xrx(b>#1un$t|85glf;}QA_<4TE%I}s|@XO{O45$0+cR( zbPhq#bO1Cp$PIxV!KenN1djx!d?hGas}sLY9%_fk3|sl zQkK#bm~wYKciD4GCnMG>=q+Q4YA=eLr*+x}|mEV?au1*~(DvPzj{kd{geS=g=yD_go;|ClY;) zMje1Cpmenz8^9ETmVIB#oXFa=AI+67p_H!xrCCVrYkD3EYSMz7QZPD~HtLuzd$ZTLM%AOb(zNPBkEn{b|RA{s-p`C|!vq1cD$awQxoXOgUKcg!)p_ zV#))Ws17atRBn|08r!y^kTPT$%TS7_nDtY>$LEsf0%_{p0A>)NbVZFApcR7F-7aV= z#l^ss&k>a1s0GkS3#pd&Nz0L%0@JbDuC)csq|!t2_d>3Gxs6*)Q_}-NmiM)RC}0~< z3JtKDKoGRfHXsG2vNPpYQ+njqQTg0z=sZ$bOZNwvR5E?~EwzCKeJ(Ulbf~*N2bv-1 zsP`IHbb=rVI*fK%87?-jQ-ew^zo@oKQ_MPgo)*$IK~T&!o|fu{u693a)QG+^y^ z2v7<^5CkyY8%$$Rs?870v5v~+PGiTtRu9jvP?nmrnS#oYHC3i}($==m32Xw8LV!{T zf*=5D5==v&n1W0VPIIH|4-sv@c6iMVd`ekOHP?O&Vq^Qvfla_D1So|d2wEwe?h2;# zS|-BZ1w^N?a?>%u@x1q$yXsR2G*gz8Yb6~5 zqX1F}Pzpg11dRrzy8>sZ4!G^-0jnVp&4p0_DFi5mAP9m+htkltUEnmQE@&E1ngg3T z@R?(wg`lYj%Zx%01kC_kBslW-Qg9)cGflw>AoYA9bO@B@!YTyK^8SFO6oMdVI@)Cg zDEVH>JrC%dE|8`^w~u8M5DNiHAqaw?QK2*kOm_iL!0Pybd8qyEGfxyi3QbjT-$M`t zO%!%wkf?nQu(4dQ-FI#%t_^4w_XI4Z5ClQf)voURp>;s>gjWD51So|d2!bXBrU21( z!zq9iT7owC3LprA03#5t0SG$!bq-4@1VPZebZ9FmtgO?5OMoZ@D1{&hf&i@0D&ZD_ zjv=`3Aqav1D-eET2s*lu5(images/deviceID-0402.svg images/gcs-board-cc.png images/gcs-board-cc3d.png + images/pipx.png From 06e9fe0a283dbcbe6549b9eb1d155d1b3ea5549c Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sat, 21 Jul 2012 10:07:47 -0700 Subject: [PATCH 056/543] removed all the pushbutton stylesheets, fixed the scrollbar area colors, compacted UI a bit more for smaller screens, misc text changes --- .../src/plugins/config/airframe.ui | 45 +- .../src/plugins/config/camerastabilization.ui | 320 ++++----- .../src/plugins/config/configoutputwidget.cpp | 3 + .../config/configstabilizationwidget.cpp | 33 +- .../openpilotgcs/src/plugins/config/input.ui | 43 +- .../openpilotgcs/src/plugins/config/output.ui | 127 ++-- .../src/plugins/config/pipxtreme.ui | 5 +- .../src/plugins/config/pro_hw_settings.ui | 7 +- .../src/plugins/config/stabilization.ui | 680 ++++++++---------- .../openpilotgcs/src/plugins/config/txpid.ui | 45 +- 10 files changed, 519 insertions(+), 789 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 1221aae5d..85abfa7af 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -2977,7 +2977,7 @@ p, li { white-space: pre-wrap; } <table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;"> <tr> <td style="border: none;"> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD IS DANGEROUS</span></p> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD REQUIRES CAUTION</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</p> <p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</p></td></tr></table></body></html> @@ -3015,6 +3015,9 @@ p, li { white-space: pre-wrap; } + + 4 + @@ -3075,25 +3078,7 @@ p, li { white-space: pre-wrap; } Send to board, but don't save permanently (flash or SD). - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Apply @@ -3112,25 +3097,7 @@ border-radius: 4; Applies and Saves all settings to flash or SD depending on board. - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Save diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index b41aac015..6b24feff8 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -132,7 +132,7 @@ 0 0 790 - 646 + 648 @@ -859,204 +859,148 @@ value. + + + 0 + 0 + + + + + 0 + 75 + + false - - - 12 - + - + + + Qt::Horizontal + + + + 425 + 20 + + + + + + + + + 0 + 0 + + + + + 32 + 32 + + + + + true + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + Ctrl+S + + + false + + + true + + + + + + + 4 + - - - - - QFrame::StyledPanel - - - QFrame::Raised - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 32 - 32 - - - - - true - - - - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 32 - 32 - - - - Ctrl+S - - - false - - - true - - - - - - - - 130 - 28 - - - - Load default CameraStabilization settings except output channels + + + + 140 + 28 + + + + Load default CameraStabilization settings except output channels Loaded settings are not applied automatically. You have to click the Apply or Save button afterwards. - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Reset To Defaults - - - - - - - - 60 - 28 - - - - Send settings to the board but do not save to the non-volatile memory - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Apply - - - - - - - - 60 - 28 - - - - Send settings to the board and save to the non-volatile memory - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Save - - - false - - - - + + + + + + Reset To Defaults + + + + + + + + 78 + 28 + + + + Send settings to the board but do not save to the non-volatile memory + + + + + + Apply + + + + + + + + 71 + 28 + + + + Send settings to the board and save to the non-volatile memory + + + + + + Save + + + false + + diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index 9b3e6e01b..6985e7561 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -47,13 +47,16 @@ #include "systemsettings.h" #include "uavsettingsimportexport/uavsettingsimportexportfactory.h" + ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent),wasItMe(false) { m_config = new Ui_OutputWidget(); m_config->setupUi(this); + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVSettingsImportExportFactory * importexportplugin = pm->getObject(); connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(stopTests())); diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 319803ca8..a535914ac 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -41,11 +41,7 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa m_stabilization = new Ui_StabilizationWidget(); m_stabilization->setupUi(this); - // To bring old style sheet back without adding it manually do this: - // Alternatively apply a global stylesheet to the QGroupBox - // setStyleSheet("QGroupBox {background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); border: 1px outset #999; border-radius: 3; }"); - //setStyleSheet("QPushButton {\nborder: 1px outset #999;\nborder-radius: 5;\nbackground-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255));\n}\n\nQPushButton:pressed {\n\n border-style: inset;\n background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255));\n\n}\n\n\nQPushButton:hover {\n border: 1px outset #999; \nborder-color: rgb(83, 83, 83);\nborder-radius: 4;\n}"); - //setStyleSheet("background-color: rgb(230, 230, 230);"); + autoLoadWidgets(); realtimeUpdates=new QTimer(this); @@ -65,20 +61,18 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa // This is needed because new style tries to compact things as much as possible in grid // and on OSX the widget sizes of PushButtons is reported incorrectly: // https://bugreports.qt-project.org/browse/QTBUG-14591 - m_stabilization->saveStabilizationToRAM_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->saveStabilizationToSD_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->stabilizationReloadBoardData_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); - // m_stabilization->saveStabilizationToRAM_7->setAttribute(Qt::WA_LayoutUsesWidgetRect); - // m_stabilization->saveStabilizationToSD_7->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->pushButton_2->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->pushButton_3->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->pushButton_4->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->pushButton_19->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->pushButton_20->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->pushButton_21->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->pushButton_22->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->pushButton_23->setAttribute(Qt::WA_LayoutUsesWidgetRect); - m_stabilization->pushButton_24->setAttribute(Qt::WA_LayoutUsesWidgetRect); +// m_stabilization->saveStabilizationToRAM_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); +// m_stabilization->saveStabilizationToSD_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); +// m_stabilization->stabilizationReloadBoardData_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); +// m_stabilization->pushButton_2->setAttribute(Qt::WA_LayoutUsesWidgetRect); +// m_stabilization->pushButton_3->setAttribute(Qt::WA_LayoutUsesWidgetRect); +// m_stabilization->pushButton_4->setAttribute(Qt::WA_LayoutUsesWidgetRect); +// m_stabilization->pushButton_19->setAttribute(Qt::WA_LayoutUsesWidgetRect); +// m_stabilization->pushButton_20->setAttribute(Qt::WA_LayoutUsesWidgetRect); +// m_stabilization->pushButton_21->setAttribute(Qt::WA_LayoutUsesWidgetRect); +// m_stabilization->pushButton_22->setAttribute(Qt::WA_LayoutUsesWidgetRect); +// m_stabilization->pushButton_23->setAttribute(Qt::WA_LayoutUsesWidgetRect); +// m_stabilization->pushButton_24->setAttribute(Qt::WA_LayoutUsesWidgetRect); } @@ -90,7 +84,6 @@ ConfigStabilizationWidget::~ConfigStabilizationWidget() void ConfigStabilizationWidget::realtimeUpdatesSlot(int value) { m_stabilization->realTimeUpdates_6->setCheckState((Qt::CheckState)value); - //m_stabilization->realTimeUpdates_7->setCheckState((Qt::CheckState)value); if(value==Qt::Checked && !realtimeUpdates->isActive()) realtimeUpdates->start(300); else if(value==Qt::Unchecked) diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index a6532ed53..a811c6754 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -1057,6 +1057,9 @@ margin:1px; + + 4 + @@ -1115,25 +1118,7 @@ margin:1px; Be sure to set the Neutral position on all sliders before sending! - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Apply @@ -1153,25 +1138,7 @@ border-radius: 4; Applies and Saves all settings to SD - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Save diff --git a/ground/openpilotgcs/src/plugins/config/output.ui b/ground/openpilotgcs/src/plugins/config/output.ui index a74281ab0..de33805a6 100644 --- a/ground/openpilotgcs/src/plugins/config/output.ui +++ b/ground/openpilotgcs/src/plugins/config/output.ui @@ -6,7 +6,7 @@ 0 0 - 866 + 811 937 @@ -113,7 +113,7 @@ 0 0 - 836 + 781 800 @@ -121,7 +121,7 @@ - + 0 0 @@ -146,7 +146,7 @@ - 25 + 5 20 @@ -230,7 +230,7 @@ - 25 + 5 20 @@ -663,7 +663,7 @@ margin:1px; - 185 + 45 0 @@ -682,7 +682,7 @@ font:bold; margin:1px; - Neutral (slowest for motor) + Neutral Qt::AlignCenter @@ -871,6 +871,42 @@ margin:1px; + + + + + 0 + 60 + + + + + + + + + + true + + + + 105 + 0 + + + + Move the servos using the sliders. Two important things: +- Take extra care if the output is connected to an motor controller! +- Will only work if the RC receiver is working (failsafe) + + + Test outputs + + + + + + @@ -881,33 +917,27 @@ margin:1px; + + + 0 + 0 + + + + + 0 + 75 + + - - - - true - - - - 105 - 0 - - - - Move the servos using the sliders. Two important things: -- Take extra care if the output is connected to an motor controller! -- Will only work if the RC receiver is working (failsafe) - - - Test outputs - - - + + 4 + @@ -972,25 +1002,7 @@ margin:1px; Be sure to set the Neutral position on all sliders before sending! - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Apply @@ -1010,25 +1022,7 @@ border-radius: 4; Applies and Saves all settings to SD - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Save @@ -1043,7 +1037,6 @@ border-radius: 4; - channelOutTest saveRCOutputToRAM saveRCOutputToSD diff --git a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui index 8a5c2dec4..557023855 100644 --- a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui +++ b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui @@ -7,7 +7,7 @@ 0 0 840 - 834 + 862 @@ -63,6 +63,9 @@ + + 4 + diff --git a/ground/openpilotgcs/src/plugins/config/pro_hw_settings.ui b/ground/openpilotgcs/src/plugins/config/pro_hw_settings.ui index 6e6751b87..4c782357c 100644 --- a/ground/openpilotgcs/src/plugins/config/pro_hw_settings.ui +++ b/ground/openpilotgcs/src/plugins/config/pro_hw_settings.ui @@ -29,9 +29,9 @@ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> +</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;"> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Set the serial speed of your onboard telemetry modem here. It is the speed between the OpenPilot board and the onboard modem, and could be different from the radio link speed.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Sans'; font-size:10pt;"></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Sans'; font-size:10pt;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware of not locking yourself out! You should only modify this setting when the OpenPilot board is connected through the USB port.</span></p></body></html> @@ -76,6 +76,9 @@ p, li { white-space: pre-wrap; } + + 4 + diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 9aa5eb445..57b250731 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -7,9 +7,21 @@ 0 0 786 - 993 + 950 + + + 0 + 0 + + + + + 350 + 0 + + @@ -450,7 +462,7 @@ - + 0 0 @@ -498,6 +510,18 @@ + + + 0 + 0 + + + + + 50 + 0 + + @@ -577,12 +601,12 @@ 0 0 756 - 856 + 817 - 12 + -1 @@ -644,8 +668,11 @@ Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + -1 + - + 4 @@ -668,6 +695,22 @@ + + + + Qt::Horizontal + + + QSizePolicy::MinimumExpanding + + + + 40 + 20 + + + + @@ -679,7 +722,7 @@ 51 - 28 + 25 @@ -695,25 +738,7 @@ false - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Wiki @@ -737,13 +762,13 @@ border-radius: 4; 81 - 28 + 25 - 81 - 28 + 16777215 + 16777215 @@ -753,25 +778,7 @@ border-radius: 4; false - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Default @@ -4109,7 +4116,7 @@ value as the Kp. - + 4 @@ -4132,6 +4139,22 @@ value as the Kp. + + + + Qt::Horizontal + + + QSizePolicy::MinimumExpanding + + + + 40 + 20 + + + + @@ -4143,32 +4166,14 @@ value as the Kp. 51 - 28 + 25 Takes you to the online wiki page for Attitude settings - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Wiki @@ -4192,32 +4197,14 @@ border-radius: 4; 81 - 28 + 25 Reset all values to GCS defaults - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Default @@ -7493,7 +7480,7 @@ border-radius: 5; - + 4 @@ -7503,12 +7490,12 @@ border-radius: 5; Qt::Horizontal - QSizePolicy::Expanding + QSizePolicy::MinimumExpanding - 474 - 13 + 40 + 20 @@ -7524,32 +7511,14 @@ border-radius: 5; 51 - 28 + 25 Takes you to the online wiki page for Stick settings - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Wiki @@ -7573,32 +7542,14 @@ border-radius: 4; 81 - 28 + 25 Reset all values to GCS defaults - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Default @@ -10611,6 +10562,78 @@ Attitude + + + + + 0 + 80 + + + + + + + + + + + 0 + 0 + + + + + 300 + 20 + + + + When the throttle is low, zero the intergral term to prevent intergral wind-up + + + + + + Zero the integral when throttle is low + + + + objname:StabilizationSettings + fieldname:LowThrottleZeroIntegral + + + + + + + + + 0 + 0 + + + + + 136 + 20 + + + + If you check this, the GCS will udpate the stabilization factors +automatically every 300ms, which will help for fast tuning. + + + + + + Update in real time + + + + + + @@ -10721,16 +10744,16 @@ Attitude 0 0 - 741 - 923 + 470 + 914 true - + - 12 + -1 @@ -10776,13 +10799,13 @@ Attitude 0 - 210 + 220 16777215 - 210 + 16777215 @@ -11312,7 +11335,7 @@ Attitude - -1 + 4 @@ -11324,6 +11347,19 @@ Attitude + + + + Qt::Horizontal + + + + 40 + 20 + + + + @@ -11335,35 +11371,20 @@ Attitude 81 - 28 + 25 - 81 - 28 + 16777215 + 16777215 + + Reset all values to GCS defaults + - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Default @@ -14269,13 +14290,13 @@ value as the Kp. 0 - 181 + 190 16777215 - 181 + 16777215 @@ -14820,6 +14841,19 @@ value as the Kp. + + + + Qt::Horizontal + + + + 40 + 20 + + + + @@ -14831,38 +14865,20 @@ value as the Kp. 81 - 28 + 25 - 81 - 28 + 16777215 + 16777215 Reset all values to GCS defaults - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Default @@ -17579,7 +17595,7 @@ border-radius: 5; 16777215 - 211 + 16777215 @@ -18118,8 +18134,8 @@ border-radius: 5; - 100 - 10 + 40 + 20 @@ -18135,38 +18151,20 @@ border-radius: 5; 81 - 28 + 25 - 81 - 28 + 16777215 + 16777215 Reset all values to GCS defaults - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Default @@ -20867,33 +20865,37 @@ rate(deg/s) - - - - 180 - 16 - - - - Sensor Tunning - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 20 - 10 - - - + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 20 + 10 + + + + + + + + + 180 + 16 + + + + Sensor Tunning + + + + @@ -20906,7 +20908,7 @@ rate(deg/s) 16777215 - 125 + 16777215 @@ -21449,7 +21451,7 @@ rate(deg/s) 459 - 10 + 20 @@ -21465,38 +21467,20 @@ rate(deg/s) 81 - 28 + 25 - 81 - 28 + 16777215 + 16777215 Reset all values to GCS defaults - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Default @@ -23774,7 +23758,7 @@ border-radius: 5; - + 0 0 @@ -23782,13 +23766,13 @@ border-radius: 5; 0 - 79 + 75 16777215 - 79 + 75 @@ -24314,58 +24298,46 @@ border-radius: 5; Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - + - 12 - - - 12 + 4 - - - + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + 4 + + + - + 0 0 - 300 - 20 - - - - When the throttle is low, zero the intergral term to prevent intergral wind-up - - - - - - Zero the integral when throttle is low - - - - objname:StabilizationSettings - fieldname:LowThrottleZeroIntegral - - - - - - - - - 130 - 28 + 140 + 25 - 130 - 28 + 16777215 + 16777215 @@ -24373,25 +24345,7 @@ border-radius: 5; Useful if you have accidentally changed some settings. - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Reload Board Data @@ -24404,43 +24358,25 @@ border-radius: 4; - + 60 - 28 + 25 - 60 - 28 + 16777215 + 16777215 Send settings to the board but do not save to the non-volatile memory - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Apply @@ -24452,43 +24388,25 @@ border-radius: 4; - + 60 - 28 + 25 - 60 - 28 + 16777215 + 16777215 Send settings to the board and save to the non-volatile memory - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Save @@ -24500,32 +24418,6 @@ border-radius: 4; - - - - - 0 - 0 - - - - - 136 - 20 - - - - If you check this, the GCS will udpate the stabilization factors -automatically every 300ms, which will help for fast tuning. - - - - - - Update in real time - - - @@ -24586,8 +24478,6 @@ automatically every 300ms, which will help for fast tuning. spinBox_26 horizontalSlider_96 spinBox_27 - lowThrottleZeroIntegral_8 - realTimeUpdates_6 stabilizationReloadBoardData_6 saveStabilizationToRAM_6 saveStabilizationToSD_6 diff --git a/ground/openpilotgcs/src/plugins/config/txpid.ui b/ground/openpilotgcs/src/plugins/config/txpid.ui index 45eb17a61..e9acbec2d 100644 --- a/ground/openpilotgcs/src/plugins/config/txpid.ui +++ b/ground/openpilotgcs/src/plugins/config/txpid.ui @@ -623,7 +623,7 @@ margin:1px; - Messsages + Messages @@ -662,6 +662,9 @@ margin:1px; + + 4 + @@ -697,25 +700,7 @@ margin:1px; Send settings to the board but do not save to the non-volatile memory - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Apply @@ -734,25 +719,7 @@ border-radius: 4; Send settings to the board and save to the non-volatile memory - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } + Save From 1d1ef0dfcef56df72d39a2c89371bc3a3f817fcb Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sat, 21 Jul 2012 10:58:05 -0700 Subject: [PATCH 057/543] removed all the pushbutton stylesheets, hid all the apply buttons --- .../configcamerastabilizationwidget.cpp | 7 +++++ .../plugins/config/configccattitudewidget.cpp | 8 +++++- .../src/plugins/config/configinputwidget.cpp | 10 +++++++ .../src/plugins/config/configoutputwidget.cpp | 9 ++++-- .../config/configstabilizationwidget.cpp | 28 ++++++++----------- .../src/plugins/config/configtxpidwidget.cpp | 7 +++++ .../config/configvehicletypewidget.cpp | 8 ++++++ 7 files changed, 58 insertions(+), 19 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index 3e757de63..c15af11b2 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -33,12 +33,19 @@ #include #include #include +#include +#include ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) { // TODO: this widget should use the addUAVObjectToWidgetRelation() m_camerastabilization = new Ui_CameraStabilizationWidget(); m_camerastabilization->setupUi(this); + + ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); + Core::Internal::GeneralSettings * settings=pm->getObject(); + if(!settings->useExpertMode()) + m_camerastabilization->camerastabilizationSaveRAM->setVisible(false); QComboBox *outputs[3] = { m_camerastabilization->rollChannel, diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp index 10064b835..044dd7770 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp @@ -35,6 +35,8 @@ #include #include "accels.h" #include "gyros.h" +#include +#include ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) : ConfigTaskWidget(parent), @@ -43,7 +45,11 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) : ui->setupUi(this); connect(ui->zeroBias,SIGNAL(clicked()),this,SLOT(startAccelCalibration())); - + ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); + Core::Internal::GeneralSettings * settings=pm->getObject(); + if(!settings->useExpertMode()) + ui->applyButton->setVisible(false); + addApplySaveButtons(ui->applyButton,ui->saveButton); addUAVObject("AttitudeSettings"); diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index 7952b3d70..769790c94 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -41,6 +41,9 @@ #include #include +#include +#include + #define ACCESS_MIN_MOVE -3 #define ACCESS_MAX_MOVE 3 #define STICK_MIN_MOVE -8 @@ -53,7 +56,14 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent) receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager()); m_config = new Ui_InputWidget(); m_config->setupUi(this); + + addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); + ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); + Core::Internal::GeneralSettings * settings=pm->getObject(); + if(!settings->useExpertMode()) + m_config->saveRCInputToRAM->setVisible(false); + addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); //Generate the rows of buttons in the input channel form GUI diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index 6985e7561..cb1918888 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -46,15 +46,20 @@ #include "systemalarms.h" #include "systemsettings.h" #include "uavsettingsimportexport/uavsettingsimportexportfactory.h" - +#include +#include ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent),wasItMe(false) { m_config = new Ui_OutputWidget(); m_config->setupUi(this); + + ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); + Core::Internal::GeneralSettings * settings=pm->getObject(); + if(!settings->useExpertMode()) + m_config->saveRCOutputToRAM->setVisible(false); - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVSettingsImportExportFactory * importexportplugin = pm->getObject(); diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index a535914ac..bc277a2c3 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -36,17 +36,27 @@ #include #include + +#include +#include + + ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) { m_stabilization = new Ui_StabilizationWidget(); m_stabilization->setupUi(this); + + ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); + Core::Internal::GeneralSettings * settings=pm->getObject(); + if(!settings->useExpertMode()) + m_stabilization->saveStabilizationToRAM_6->setVisible(false); + autoLoadWidgets(); realtimeUpdates=new QTimer(this); connect(m_stabilization->realTimeUpdates_6,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int))); - //connect(m_stabilization->realTimeUpdates_7,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int))); connect(realtimeUpdates,SIGNAL(timeout()),this,SLOT(apply())); connect(m_stabilization->checkBox_7,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int))); @@ -58,21 +68,7 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa disableMouseWheelEvents(); - // This is needed because new style tries to compact things as much as possible in grid - // and on OSX the widget sizes of PushButtons is reported incorrectly: - // https://bugreports.qt-project.org/browse/QTBUG-14591 -// m_stabilization->saveStabilizationToRAM_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); -// m_stabilization->saveStabilizationToSD_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); -// m_stabilization->stabilizationReloadBoardData_6->setAttribute(Qt::WA_LayoutUsesWidgetRect); -// m_stabilization->pushButton_2->setAttribute(Qt::WA_LayoutUsesWidgetRect); -// m_stabilization->pushButton_3->setAttribute(Qt::WA_LayoutUsesWidgetRect); -// m_stabilization->pushButton_4->setAttribute(Qt::WA_LayoutUsesWidgetRect); -// m_stabilization->pushButton_19->setAttribute(Qt::WA_LayoutUsesWidgetRect); -// m_stabilization->pushButton_20->setAttribute(Qt::WA_LayoutUsesWidgetRect); -// m_stabilization->pushButton_21->setAttribute(Qt::WA_LayoutUsesWidgetRect); -// m_stabilization->pushButton_22->setAttribute(Qt::WA_LayoutUsesWidgetRect); -// m_stabilization->pushButton_23->setAttribute(Qt::WA_LayoutUsesWidgetRect); -// m_stabilization->pushButton_24->setAttribute(Qt::WA_LayoutUsesWidgetRect); + } diff --git a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp index 30c87bd78..6c6ac1c9a 100644 --- a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp @@ -28,11 +28,18 @@ #include "configtxpidwidget.h" #include "txpidsettings.h" #include "hwsettings.h" +#include +#include ConfigTxPIDWidget::ConfigTxPIDWidget(QWidget *parent) : ConfigTaskWidget(parent) { m_txpid = new Ui_TxPIDWidget(); m_txpid->setupUi(this); + + ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); + Core::Internal::GeneralSettings * settings=pm->getObject(); + if(!settings->useExpertMode()) + m_txpid->Apply->setVisible(false); addApplySaveButtons(m_txpid->Apply, m_txpid->Save); diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 1a765a381..5c91204b4 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -41,6 +41,9 @@ #include "systemsettings.h" #include "mixersettings.h" #include "actuatorsettings.h" +#include +#include + /** Helper delegate for the custom mixer editor table. @@ -97,6 +100,11 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi { m_aircraft = new Ui_AircraftWidget(); m_aircraft->setupUi(this); + + ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); + Core::Internal::GeneralSettings * settings=pm->getObject(); + if(!settings->useExpertMode()) + m_aircraft->saveAircraftToRAM->setVisible(false); addApplySaveButtons(m_aircraft->saveAircraftToRAM,m_aircraft->saveAircraftToSD); From a53158bec180534e2139d0afcf047dc135f522d7 Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sat, 21 Jul 2012 11:26:37 -0700 Subject: [PATCH 058/543] removed all the pushbutton stylesheets, hid all the apply buttons, applied same design ideas to the HW and the attitude forms --- .../src/plugins/config/airframe.ui | 12 + .../src/plugins/config/camerastabilization.ui | 12 + .../src/plugins/config/cc_hw_settings.ui | 569 +++++++++++------- .../src/plugins/config/ccattitude.ui | 544 ++++++++++------- 4 files changed, 718 insertions(+), 419 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 85abfa7af..e3bb54aa9 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -3009,6 +3009,18 @@ p, li { white-space: pre-wrap; } + + + 0 + 0 + + + + + 0 + 75 + + diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index 6b24feff8..116bab28a 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -837,6 +837,18 @@ value. + + + 0 + 0 + + + + + 0 + 50 + + false diff --git a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui index e64800124..3c9540105 100644 --- a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui +++ b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui @@ -6,210 +6,347 @@ 0 0 - 517 - 487 + 691 + 849 Form - + + + 12 + - - - QFrame::StyledPanel + + + 0 - - QFrame::Raised + + + HW settings + + + + 0 + + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + + + QFrame::NoFrame + + + QFrame::Plain + + + true + + + + + 0 + 0 + 661 + 652 + + + + + + + + + + + + true + + + + + + + + + + + + + MainPort + + + Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft + + + + + + + + + + + + + + FlexiPort + + + Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + USB HID Port + + + Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft + + + + + + + + + + USB VCP Port + + + Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft + + + + + + + + + + RcvrPort + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + + + + + + + Telemetry speed: + + + + + + + + 55 + 0 + + + + GPS speed: + + + + + + + + 55 + 0 + + + + ComUsbBridge speed: + + + + + + + Select the speed here. + + + + + + + Select the speed here. + + + + + + + Select the speed here. + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + Qt::Vertical + + + + 20 + 328 + + + + + + + + + 75 + true + + + + Changes on this page only take effect after board reset or power cycle + + + Qt::AlignCenter + + + true + + + + + + + + + + + + + + + + 0 + 0 + - - - - - - - - - - true - - - - - - - - - - - - - MainPort - - - Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft - - - - - - - - - - - - - - FlexiPort - - - Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - USB HID Port - - - Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft - - - - - - - - - - USB VCP Port - - - Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft - - - - - - - - - - RcvrPort - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - - - - - - - Telemetry speed: - - - - - - - - 55 - 0 - - - - GPS speed: - - - - - - - - 55 - 0 - - - - ComUsbBridge speed: - - - - - - - Select the speed here. - - - - - - - Select the speed here. - - - - - - - Select the speed here. - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - + + + 0 + 50 + + + + Problems + + @@ -229,24 +366,32 @@ - - - - - 75 - true - - - - Changes on this page only take effect after board reset or power cycle - - - true - - - + + + + + + + + 0 + 0 + + + + + 0 + 75 + + + + + + + + 4 + diff --git a/ground/openpilotgcs/src/plugins/config/ccattitude.ui b/ground/openpilotgcs/src/plugins/config/ccattitude.ui index 49a7ab649..c3585866b 100644 --- a/ground/openpilotgcs/src/plugins/config/ccattitude.ui +++ b/ground/openpilotgcs/src/plugins/config/ccattitude.ui @@ -6,226 +6,356 @@ 0 0 - 455 - 428 + 606 + 576 Form - - - - - Rotate virtual attitude relative to board + + + + + 0 - - - - - Roll - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - - -180 - - - 180 - - - - - - - Pitch - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - - -90 - - - 90 - - - - - - - Yaw - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - - -180 - - - 180 - - - - - - - - - - Calibration - - - - - - Place aircraft very flat, and then click level to compute the accelerometer and gyro bias - - - true - - - - - - - Launch horizontal calibration. - - - Level - - - - - - - 0 - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 0 - 10 - - - - - - - - If enabled, a fast recalibration of gyro zero point will be done + + + Attitude + + + + 0 + + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + + + QFrame::NoFrame + + + QFrame::Plain + + + true + + + + + 0 + 0 + 576 + 439 + + + + + + + Rotate virtual attitude relative to board + + + + + + Roll + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + -180 + + + 180 + + + + + + + Pitch + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + -90 + + + 90 + + + + + + + Yaw + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + -180 + + + 180 + + + + + + + + + + Calibration + + + + + + Place aircraft very flat, and then click level to compute the accelerometer and gyro bias + + + true + + + + + + + Launch horizontal calibration. + + + Level + + + + + + + 0 + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 0 + 10 + + + + + + + + If enabled, a fast recalibration of gyro zero point will be done whenever the frame is armed. Do not move the airframe while arming it in that case! + + + Zero gyros while arming aircraft + + + + + + + + + + Qt::Vertical + + + + 20 + 91 + + + + + + + + + + + + + + + + + 0 + 0 + + + + + 0 + 75 + + + + + + + + + + 4 - - Zero gyros while arming aircraft - - + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 32 + 32 + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + true + + + + + + + Apply + + + + + + + Click to permanently save the accel bias in the CopterControl Flash. + + + Save + + + + - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 32 - 32 - - - - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 32 - 32 - - - - true - - - - - - - Apply - - - - - - - Click to permanently save the accel bias in the CopterControl Flash. - - - Save - - - - - From 54dae87017e02496dbd496dcae26d8a6e980acdb Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sat, 21 Jul 2012 12:28:55 -0700 Subject: [PATCH 059/543] fixed the hw settings apply button autofill, removed commented lines from the config_cc_hw_widget.cpp file --- .../src/plugins/config/cc_hw_settings.ui | 77 +++++++++++++++++-- .../plugins/config/config_cc_hw_widget.cpp | 8 +- 2 files changed, 72 insertions(+), 13 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui index 3c9540105..e9c3d7aaf 100644 --- a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui +++ b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui @@ -6,17 +6,14 @@ 0 0 - 691 - 849 + 592 + 763 Form - - 12 - @@ -110,8 +107,8 @@ 0 0 - 661 - 652 + 547 + 651 @@ -445,12 +442,76 @@ + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + Send to OpenPilot but don't write in SD. Beware of not locking yourself out! - true + false diff --git a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp index 35a3f4c9a..f9dc84350 100644 --- a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp @@ -35,11 +35,9 @@ #include #include #include - -////Added to allow expert mode #include #include -//// + ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent) { @@ -48,12 +46,12 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent) m_telemetry->label_2->setPixmap(QPixmap(":/configgadget/images/coptercontrol.svg")); -////Added to allow expert mode + ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); Core::Internal::GeneralSettings * settings=pm->getObject(); if(!settings->useExpertMode()) m_telemetry->saveTelemetryToRAM->setVisible(false); -////////////////////////////////// + addApplySaveButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD); addUAVObjectToWidgetRelation("HwSettings","CC_FlexiPort",m_telemetry->cbFlexi); From 6ee34931ac7cdfaeff81a176bea159160d17dc54 Mon Sep 17 00:00:00 2001 From: Dmytro Poplavskiy Date: Mon, 23 Jul 2012 12:21:34 +1000 Subject: [PATCH 060/543] Expose SVG elements geometry to QML side This allows to reuse the existing svg file like pfd.svg without manually positioning individual svg element. --- .../plugins/qmlview/qmlviewgadgetwidget.cpp | 16 ++-- .../src/plugins/qmlview/svgimageprovider.cpp | 74 ++++++++++++++----- .../src/plugins/qmlview/svgimageprovider.h | 8 +- 3 files changed, 73 insertions(+), 25 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetwidget.cpp index cc4efe78d..a4c8f4f43 100644 --- a/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetwidget.cpp @@ -31,15 +31,11 @@ #include "uavobjectmanager.h" #include "uavobject.h" -#include -#include -#include #include -#include +#include #include #include #include -#include #include #include @@ -69,6 +65,8 @@ QmlViewGadgetWidget::QmlViewGadgetWidget(QWidget *parent) : else qWarning() << "Failed to load object" << objectName; } + + engine()->rootContext()->setContextProperty("qmlWidget", this); } QmlViewGadgetWidget::~QmlViewGadgetWidget() @@ -80,8 +78,12 @@ void QmlViewGadgetWidget::setQmlFile(QString fn) m_fn = fn; engine()->removeImageProvider("svg"); - engine()->addImageProvider("svg", - new SvgImageProvider(fn)); + SvgImageProvider *svgProvider = new SvgImageProvider(fn); + engine()->addImageProvider("svg", svgProvider); + + //it's necessary to allow qml side to query svg element position + engine()->rootContext()->setContextProperty("svgRenderer", svgProvider); + engine()->setBaseUrl(QUrl::fromLocalFile(fn)); qDebug() << Q_FUNC_INFO << fn; setSource(QUrl::fromLocalFile(fn)); diff --git a/ground/openpilotgcs/src/plugins/qmlview/svgimageprovider.cpp b/ground/openpilotgcs/src/plugins/qmlview/svgimageprovider.cpp index f44658090..e0f571369 100644 --- a/ground/openpilotgcs/src/plugins/qmlview/svgimageprovider.cpp +++ b/ground/openpilotgcs/src/plugins/qmlview/svgimageprovider.cpp @@ -31,6 +31,7 @@ #include SvgImageProvider::SvgImageProvider(const QString &basePath): + QObject(), QDeclarativeImageProvider(QDeclarativeImageProvider::Image), m_basePath(basePath) { @@ -41,6 +42,30 @@ SvgImageProvider::~SvgImageProvider() qDeleteAll(m_renderers); } +QSvgRenderer *SvgImageProvider::loadRenderer(const QString &svgFile) +{ + QSvgRenderer *renderer = m_renderers.value(svgFile); + if (!renderer) { + renderer = new QSvgRenderer(svgFile); + + QString fn = QUrl::fromLocalFile(m_basePath).resolved(svgFile).toLocalFile(); + + //convert path to be relative to base + if (!renderer->isValid()) + renderer->load(fn); + + if (!renderer->isValid()) { + qWarning() << "Failed to load svg file:" << svgFile << fn; + delete renderer; + return 0; + } + + m_renderers.insert(svgFile, renderer); + } + + return renderer; +} + /** requestedSize is realted to the whole svg file, not to specific element */ @@ -58,23 +83,9 @@ QImage SvgImageProvider::requestImage(const QString &id, QSize *size, const QSiz if (size) *size = QSize(); - QSvgRenderer *renderer = m_renderers.value(svgFile); - if (!renderer) { - renderer = new QSvgRenderer(svgFile); - - QString fn = QUrl::fromLocalFile(m_basePath).resolved(svgFile).toLocalFile(); - - //convert path to be relative to base - if (!renderer->isValid()) - renderer->load(fn); - - if (!renderer->isValid()) { - qWarning() << "Failed to load svg file:" << svgFile << fn; - return QImage(); - } - - m_renderers.insert(svgFile, renderer); - } + QSvgRenderer *renderer = loadRenderer(svgFile); + if (!renderer) + return QImage(); qreal xScale = 1.0; qreal yScale = 1.0; @@ -128,3 +139,32 @@ QPixmap SvgImageProvider::requestPixmap(const QString &id, QSize *size, const QS { return QPixmap::fromImage(requestImage(id, size, requestedSize)); } + +/*! + \fn SvgImageProvider::scaledElementBounds(const QString &svgFile, const QString &element) + + Returns the bound of \a element in logical coordinates, + scalled to the default size of svg document (so the bounds of whole doc would be (0,0,1,1) ). +*/ +QRectF SvgImageProvider::scaledElementBounds(const QString &svgFile, const QString &elementName) +{ + QSvgRenderer *renderer = loadRenderer(svgFile); + + if (!renderer) + return QRectF(); + + if (!renderer->elementExists(elementName)) { + qWarning() << "invalid element:" << elementName << "of" << svgFile; + return QRectF(); + } + + QRectF elementBounds = renderer->boundsOnElement(elementName); + QMatrix matrix = renderer->matrixForElement(elementName); + elementBounds = matrix.mapRect(elementBounds); + + QSize docSize = renderer->defaultSize(); + return QRectF(elementBounds.x()/docSize.width(), + elementBounds.y()/docSize.height(), + elementBounds.width()/docSize.width(), + elementBounds.height()/docSize.height()); +} diff --git a/ground/openpilotgcs/src/plugins/qmlview/svgimageprovider.h b/ground/openpilotgcs/src/plugins/qmlview/svgimageprovider.h index 1bcc20cee..50fd0f7bb 100644 --- a/ground/openpilotgcs/src/plugins/qmlview/svgimageprovider.h +++ b/ground/openpilotgcs/src/plugins/qmlview/svgimageprovider.h @@ -28,19 +28,25 @@ #ifndef SVGIMAGEPROVIDER_H_ #define SVGIMAGEPROVIDER_H_ +#include #include #include #include -class SvgImageProvider : public QDeclarativeImageProvider +class SvgImageProvider : public QObject, public QDeclarativeImageProvider { + Q_OBJECT public: SvgImageProvider(const QString &basePath); ~SvgImageProvider(); + QSvgRenderer *loadRenderer(const QString &svgFile); + QImage requestImage(const QString &id, QSize *size, const QSize& requestedSize); QPixmap requestPixmap(const QString &id, QSize *size, const QSize& requestedSize); + Q_INVOKABLE QRectF scaledElementBounds(const QString &svgFile, const QString &elementName); + private: QMap m_renderers; QString m_basePath; From 69eb685d7ba0af6c9b732bd5ad620cde46bbaa49 Mon Sep 17 00:00:00 2001 From: Dmytro Poplavskiy Date: Mon, 23 Jul 2012 15:36:53 +1000 Subject: [PATCH 061/543] Moved svgimageprovider from qmlview plugin to utils lib To be reused by other qml based plugins. --- .../qmlview => libs/utils}/svgimageprovider.cpp | 0 .../qmlview => libs/utils}/svgimageprovider.h | 0 ground/openpilotgcs/src/libs/utils/utils.pro | 12 +++++++++--- ground/openpilotgcs/src/plugins/qmlview/qmlview.pro | 7 +++---- .../src/plugins/qmlview/qmlviewgadgetwidget.cpp | 1 + .../src/plugins/qmlview/qmlviewgadgetwidget.h | 1 - 6 files changed, 13 insertions(+), 8 deletions(-) rename ground/openpilotgcs/src/{plugins/qmlview => libs/utils}/svgimageprovider.cpp (100%) rename ground/openpilotgcs/src/{plugins/qmlview => libs/utils}/svgimageprovider.h (100%) diff --git a/ground/openpilotgcs/src/plugins/qmlview/svgimageprovider.cpp b/ground/openpilotgcs/src/libs/utils/svgimageprovider.cpp similarity index 100% rename from ground/openpilotgcs/src/plugins/qmlview/svgimageprovider.cpp rename to ground/openpilotgcs/src/libs/utils/svgimageprovider.cpp diff --git a/ground/openpilotgcs/src/plugins/qmlview/svgimageprovider.h b/ground/openpilotgcs/src/libs/utils/svgimageprovider.h similarity index 100% rename from ground/openpilotgcs/src/plugins/qmlview/svgimageprovider.h rename to ground/openpilotgcs/src/libs/utils/svgimageprovider.h diff --git a/ground/openpilotgcs/src/libs/utils/utils.pro b/ground/openpilotgcs/src/libs/utils/utils.pro index 003497b4d..e7390ad77 100644 --- a/ground/openpilotgcs/src/libs/utils/utils.pro +++ b/ground/openpilotgcs/src/libs/utils/utils.pro @@ -5,7 +5,8 @@ QT += gui \ network \ xml \ svg \ - opengl + opengl \ + declarative DEFINES += QTCREATOR_UTILS_LIB @@ -51,7 +52,9 @@ SOURCES += reloadpromptutils.cpp \ mytabbedstackwidget.cpp \ mytabwidget.cpp \ mylistwidget.cpp \ - cachedsvgitem.cpp + cachedsvgitem.cpp \ + svgimageprovider.cpp + SOURCES += xmlconfig.cpp win32 { @@ -106,7 +109,10 @@ HEADERS += utils_global.h \ mytabbedstackwidget.h \ mytabwidget.h \ mylistwidget.h \ - cachedsvgitem.h + cachedsvgitem.h \ + svgimageprovider.h + + HEADERS += xmlconfig.h FORMS += filewizardpage.ui \ diff --git a/ground/openpilotgcs/src/plugins/qmlview/qmlview.pro b/ground/openpilotgcs/src/plugins/qmlview/qmlview.pro index 5b2817e6d..c2897f3a0 100644 --- a/ground/openpilotgcs/src/plugins/qmlview/qmlview.pro +++ b/ground/openpilotgcs/src/plugins/qmlview/qmlview.pro @@ -14,8 +14,8 @@ HEADERS += \ qmlviewgadgetwidget.h \ qmlviewgadgetfactory.h \ qmlviewgadgetconfiguration.h \ - qmlviewgadgetoptionspage.h \ - svgimageprovider.h + qmlviewgadgetoptionspage.h + SOURCES += \ qmlviewplugin.cpp \ @@ -23,8 +23,7 @@ SOURCES += \ qmlviewgadgetfactory.cpp \ qmlviewgadgetwidget.cpp \ qmlviewgadgetconfiguration.cpp \ - qmlviewgadgetoptionspage.cpp \ - svgimageprovider.cpp + qmlviewgadgetoptionspage.cpp OTHER_FILES += QMLView.pluginspec diff --git a/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetwidget.cpp index a4c8f4f43..26e03b0e8 100644 --- a/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetwidget.cpp @@ -30,6 +30,7 @@ #include "extensionsystem/pluginmanager.h" #include "uavobjectmanager.h" #include "uavobject.h" +#include "utils/svgimageprovider.h" #include #include diff --git a/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetwidget.h b/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetwidget.h index d0af0533b..d3019de36 100644 --- a/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetwidget.h @@ -29,7 +29,6 @@ #define QMLVIEWGADGETWIDGET_H_ #include "qmlviewgadgetconfiguration.h" -#include "svgimageprovider.h" #include From f95bd8bc1bd43ffc2322535d129346a6b727a52b Mon Sep 17 00:00:00 2001 From: Dmytro Poplavskiy Date: Mon, 23 Jul 2012 17:19:24 +1000 Subject: [PATCH 062/543] Initial implementation of QML based PFD widget It uses the same pfd.svg file as original PFD widget; depends on osgearth for terrain rendering --- .../pfd/default/AltitudeScale.qml | 83 +++++ .../share/openpilotgcs/pfd/default/Pfd.qml | 120 +++++++ .../pfd/default/PfdIndicators.qml | 70 ++++ .../openpilotgcs/pfd/default/SpeedScale.qml | 91 +++++ .../share/openpilotgcs/pfd/default/srtm.earth | 26 ++ .../openpilotgcs/pfd/default/yahoo_srtm.earth | 26 ++ .../src/plugins/coreplugin/OpenPilotGCS.xml | 24 ++ .../src/plugins/pfdqml/PfdQml.pluginspec | 12 + .../src/plugins/pfdqml/osgearth.cpp | 311 ++++++++++++++++++ .../src/plugins/pfdqml/osgearth.h | 117 +++++++ .../src/plugins/pfdqml/pfdqml.pro | 35 ++ .../plugins/pfdqml/pfdqml_dependencies.pri | 1 + .../src/plugins/pfdqml/pfdqmlgadget.cpp | 44 +++ .../src/plugins/pfdqml/pfdqmlgadget.h | 45 +++ .../pfdqml/pfdqmlgadgetconfiguration.cpp | 67 ++++ .../pfdqml/pfdqmlgadgetconfiguration.h | 48 +++ .../plugins/pfdqml/pfdqmlgadgetfactory.cpp | 49 +++ .../src/plugins/pfdqml/pfdqmlgadgetfactory.h | 41 +++ .../pfdqml/pfdqmlgadgetoptionspage.cpp | 77 +++++ .../plugins/pfdqml/pfdqmlgadgetoptionspage.h | 54 +++ .../plugins/pfdqml/pfdqmlgadgetoptionspage.ui | 135 ++++++++ .../src/plugins/pfdqml/pfdqmlgadgetwidget.cpp | 106 ++++++ .../src/plugins/pfdqml/pfdqmlgadgetwidget.h | 51 +++ .../src/plugins/pfdqml/pfdqmlplugin.cpp | 55 ++++ .../src/plugins/pfdqml/pfdqmlplugin.h | 36 ++ ground/openpilotgcs/src/plugins/plugins.pro | 7 +- 26 files changed, 1730 insertions(+), 1 deletion(-) create mode 100644 ground/openpilotgcs/share/openpilotgcs/pfd/default/AltitudeScale.qml create mode 100644 ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml create mode 100644 ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdIndicators.qml create mode 100644 ground/openpilotgcs/share/openpilotgcs/pfd/default/SpeedScale.qml create mode 100644 ground/openpilotgcs/share/openpilotgcs/pfd/default/srtm.earth create mode 100644 ground/openpilotgcs/share/openpilotgcs/pfd/default/yahoo_srtm.earth create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/PfdQml.pluginspec create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/osgearth.cpp create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/osgearth.h create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqml_dependencies.pri create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.h create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.cpp create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.h create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetfactory.cpp create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetfactory.h create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.h create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.h create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlplugin.cpp create mode 100644 ground/openpilotgcs/src/plugins/pfdqml/pfdqmlplugin.h diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/AltitudeScale.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/AltitudeScale.qml new file mode 100644 index 000000000..6e5b608f7 --- /dev/null +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/AltitudeScale.qml @@ -0,0 +1,83 @@ +import Qt 4.7 + +Item { + id: sceneItem + property variant sourceSize + + Image { + id: altitude_bg + source: "image://svg/pfd.svg!altitude-bg" + sourceSize: sceneItem.sourceSize + clip: true + + property variant scaledBounds: svgRenderer.scaledElementBounds("pfd.svg", "altitude-bg") + + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + + Image { + id: altitude_scale + + source: "image://svg/pfd.svg!altitude-scale" + sourceSize: sceneItem.sourceSize + + anchors.verticalCenter: parent.verticalCenter + // The altitude scale represents 30 meters, + // move it in 0..5m range + anchors.verticalCenterOffset: -height/30 * (PositionActual.Down-Math.floor(PositionActual.Down/5)*5) + anchors.left: parent.left + + property int topNumber: 15-Math.floor(PositionActual.Down/5)*5 + + // Altitude numbers + Column { + Repeater { + model: 7 + Item { + height: altitude_scale.height / 6 + width: altitude_bg.width + + Text { + text: altitude_scale.topNumber - index*5 + color: "white" + font.pixelSize: parent.height / 4 + font.family: "Arial" + + anchors.horizontalCenter: parent.horizontalCenter + anchors.verticalCenter: parent.top + } + } + } + } + } + } + + + Image { + id: altitude_window + clip: true + + source: "image://svg/pfd.svg!altitude-window" + sourceSize: sceneItem.sourceSize + + property variant scaledBounds: svgRenderer.scaledElementBounds("pfd.svg", "altitude-window") + + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + + Text { + id: altitude_text + text: Math.floor(-PositionActual.Down).toFixed() + color: "white" + font { + family: "Arial" + pixelSize: parent.height * 0.6 + } + anchors.centerIn: parent + } + } +} diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml new file mode 100644 index 000000000..517aa5b6a --- /dev/null +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml @@ -0,0 +1,120 @@ +import Qt 4.7 +import "." +import org.OpenPilot 1.0 +//import "/home/dima/work/RC/OsgEarthQml-build-desktop-Qt_4_8_1_in_PATH__System__Debug" + +Rectangle { + color: "#666666" + + Image { + id: background + source: "image://svg/pfd.svg!background" + + fillMode: Image.PreserveAspectFit + anchors.fill: parent + + sourceSize.width: width + sourceSize.height: height + + Item { + id: sceneItem + width: parent.paintedWidth + height: parent.paintedHeight + anchors.centerIn: parent + clip: true + + Image { + id: world + source: "image://svg/pfd.svg!world" + sourceSize: background.sourceSize + smooth: true + visible: !qmlWidget.terrainEnabled + + transform: [ + Translate { + id: pitchTranslate + x: (world.parent.width - world.width)/2 + y: (world.parent.height - world.height)/2 + AttitudeActual.Pitch*world.parent.height/94 + }, + Rotation { + angle: -AttitudeActual.Roll + origin.x : world.parent.width/2 + origin.y : world.parent.height/2 + } + ] + } + + OsgEarth { + id: earthView + + anchors.fill: parent + sceneFile: qmlWidget.earthFile + visible: qmlWidget.terrainEnabled + + fieldOfView: 90 + + yaw: AttitudeActual.Yaw + pitch: AttitudeActual.Pitch + roll: AttitudeActual.Roll + + + latitude: -27.935474 + longitude: 153.187147 + altitude: 3000 + //altitude: PositionActual.Down + } + + Image { + id: rollscale + source: "image://svg/pfd.svg!rollscale" + sourceSize: background.sourceSize + smooth: true + + transformOrigin: Item.Center + rotation: -AttitudeActual.Roll + } + + Image { + id: foreground + source: "image://svg/pfd.svg!foreground" + sourceSize: background.sourceSize + anchors.centerIn: parent + } + + Image { + id: compass + source: "image://svg/pfd.svg!compass" + sourceSize: background.sourceSize + clip: true + + y: 12 + anchors.horizontalCenter: parent.horizontalCenter + + Image { + id: compass_band + source: "image://svg/pfd.svg!compass-band" + sourceSize: background.sourceSize + + anchors.centerIn: parent + //the band is 540 degrees wide + anchors.horizontalCenterOffset: -1*AttitudeActual.Yaw/540*width + } + } + + SpeedScale { + anchors.fill: parent + sourceSize: background.sourceSize + } + + AltitudeScale { + anchors.fill: parent + sourceSize: background.sourceSize + } + + PfdIndicators { + anchors.fill: parent + sourceSize: background.sourceSize + } + } + } +} diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdIndicators.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdIndicators.qml new file mode 100644 index 000000000..d520dcf00 --- /dev/null +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdIndicators.qml @@ -0,0 +1,70 @@ +import Qt 4.7 + +Item { + id: sceneItem + property variant sourceSize + + //telemetry status arrow + Image { + id: telemetry_status + source: "image://svg/pfd.svg!gcstelemetry-"+statusName + sourceSize: sceneItem.sourceSize + + property string statusName : ["Disconnected","HandshakeReq","HandshakeAck","Connected"][GCSTelemetryStats.Status] + + property variant scaledBounds: svgRenderer.scaledElementBounds("pfd.svg", "gcstelemetry-Disconnected") + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + } + + //telemetry rate text + Text { + id: telemetry_rate + text: GCSTelemetryStats.TxDataRate.toFixed()+"/"+GCSTelemetryStats.RxDataRate.toFixed() + color: "white" + font.family: "Arial" + font.pixelSize: telemetry_status.height * 0.75 + + anchors.top: telemetry_status.bottom + anchors.horizontalCenter: telemetry_status.horizontalCenter + } + + Text { + id: gps_text + text: "GPS: " + GPSPosition.Satellites + "\nPDP: " + GPSPosition.PDOP + color: "white" + font.family: "Arial" + font.pixelSize: telemetry_status.height * 0.75 + + visible: GPSPosition.Satellites > 0 + + property variant scaledBounds: svgRenderer.scaledElementBounds("pfd.svg", "gps-txt") + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height + } + + Text { + id: battery_text + + text: FlightBatteryState.Voltage.toFixed(2)+" V\n" + + FlightBatteryState.Current.toFixed(2)+" A\n" + + FlightBatteryState.ConsumedEnergy.toFixed()+" mAh" + + + color: "white" + font.family: "Arial" + + //I think it should be pixel size, + //but making it more consistent with C++ version instead + font.pointSize: scaledBounds.height * sceneItem.height + + visible: FlightBatteryState.Voltage > 0 || FlightBatteryState.Current > 0 + + property variant scaledBounds: svgRenderer.scaledElementBounds("pfd.svg", "battery-txt") + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height + + } +} diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/SpeedScale.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/SpeedScale.qml new file mode 100644 index 000000000..ddc82b571 --- /dev/null +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/SpeedScale.qml @@ -0,0 +1,91 @@ +import Qt 4.7 + +Item { + id: sceneItem + property variant sourceSize + property real groundSpeed : 3.6 * Math.sqrt(Math.pow(VelocityActual.North,2)+ + Math.pow(VelocityActual.East,2)) + + Image { + id: speed_bg + source: "image://svg/pfd.svg!speed-bg" + sourceSize: sceneItem.sourceSize + clip: true + + property variant scaledBounds: svgRenderer.scaledElementBounds("pfd.svg", "speed-bg") + + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + + Image { + id: speed_scale + + source: "image://svg/pfd.svg!speed-scale" + sourceSize: sceneItem.sourceSize + + anchors.verticalCenter: parent.verticalCenter + // The speed scale represents 30 meters, + // move it in 0..5m range + anchors.verticalCenterOffset: height/30 * (sceneItem.groundSpeed-Math.floor(sceneItem.groundSpeed/5)*5) + anchors.right: parent.right + + property int topNumber: Math.floor(sceneItem.groundSpeed/5)*5+15 + + // speed numbers + Column { + width: speed_bg.width + anchors.right: speed_scale.right + + Repeater { + model: 7 + Item { + height: speed_scale.height / 6 + width: speed_bg.width + + Text { + //don't show negative numbers + text: speed_scale.topNumber - index*5 + color: "white" + visible: speed_scale.topNumber - index*5 >= 0 + + font.pixelSize: parent.height / 4 + font.family: "Arial" + + anchors.horizontalCenter: parent.horizontalCenter + anchors.verticalCenter: parent.top + } + } + } + } + } + } + + + Image { + id: speed_window + clip: true + + source: "image://svg/pfd.svg!speed-window" + sourceSize: sceneItem.sourceSize + + property variant scaledBounds: svgRenderer.scaledElementBounds("pfd.svg", "speed-window") + + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + + Text { + id: speed_text + text: Math.round(sceneItem.groundSpeed).toFixed() + color: "white" + font { + family: "Arial" + pixelSize: parent.height * 0.6 + } + anchors.centerIn: parent + } + } +} diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/srtm.earth b/ground/openpilotgcs/share/openpilotgcs/pfd/default/srtm.earth new file mode 100644 index 000000000..bd17c7eb0 --- /dev/null +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/srtm.earth @@ -0,0 +1,26 @@ + + + + + + http://demo.pelicanmapping.com/rmweb/data/bluemarble-tms/tms.xml + + + + http://demo.pelicanmapping.com/rmweb/data/srtm30_plus_tms/tms.xml + + + + true + + 1 + + + + + diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/yahoo_srtm.earth b/ground/openpilotgcs/share/openpilotgcs/pfd/default/yahoo_srtm.earth new file mode 100644 index 000000000..1033290b5 --- /dev/null +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/yahoo_srtm.earth @@ -0,0 +1,26 @@ + + + + + + satellite + + + + http://demo.pelicanmapping.com/rmweb/data/srtm30_plus_tms/tms.xml + + + + false + + 2 + + + + + diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml index d61dba982..ac8ac26cc 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml @@ -1691,6 +1691,30 @@ + + + + false + 0.0.0 + + + false + %%DATAPATH%%pfd/default/Pfd.qml + %%DATAPATH%%pfd/default/srtm.earth + + + + + false + 0.0.0 + + + true + %%DATAPATH%%pfd/default/Pfd.qml + %%DATAPATH%%pfd/default/srtm.earth + + + diff --git a/ground/openpilotgcs/src/plugins/pfdqml/PfdQml.pluginspec b/ground/openpilotgcs/src/plugins/pfdqml/PfdQml.pluginspec new file mode 100644 index 000000000..563bacefd --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/PfdQml.pluginspec @@ -0,0 +1,12 @@ + + The OpenPilot Project + (C) 2010 Edouard Lafargue + (C) 2012 Dmytro Poplavskiy + The GNU Public License (GPL) Version 3 + QML based PFD widget + http://www.openpilot.org + + + + + diff --git a/ground/openpilotgcs/src/plugins/pfdqml/osgearth.cpp b/ground/openpilotgcs/src/plugins/pfdqml/osgearth.cpp new file mode 100644 index 000000000..b4e8ac53e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/osgearth.cpp @@ -0,0 +1,311 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "osgearth.h" + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +OsgEarthItem::OsgEarthItem(QDeclarativeItem *parent): + QDeclarativeItem(parent), + m_fbo(0), + m_currentSize(640, 480), + m_roll(0.0), + m_pitch(0.0), + m_yaw(0.0), + m_latitude(-28.5), + m_longitude(153.0), + m_altitude(400.0), + m_fieldOfView(90.0), + m_sceneFile(QLatin1String("/usr/share/osgearth/maps/srtm.earth")), + m_cameraDirty(false) +{ + setSize(m_currentSize); + setFlag(ItemHasNoContents, false); +} + +OsgEarthItem::~OsgEarthItem() +{ +} + +void OsgEarthItem::geometryChanged(const QRectF &newGeometry, const QRectF &oldGeometry) +{ + Q_UNUSED(oldGeometry); + Q_UNUSED(newGeometry); + + //Dynamic gyometry changes are not supported yet, + //terrain is rendered to fixed geompetry and scalled for now + + /* + qDebug() << Q_FUNC_INFO << newGeometry; + + int w = qRound(newGeometry.width()); + int h = qRound(newGeometry.height()); + + if (m_currentSize != QSize(w,h) && m_gw.get()) { + m_currentSize = QSize(w,h); + + m_gw->getEventQueue()->windowResize(0,0,w,h); + m_gw->resized(0,0,w,h); + + osg::Camera *camera = m_viewer->getCamera(); + camera->setViewport(new osg::Viewport(0,0,w,h)); + camera->setProjectionMatrixAsPerspective(m_fieldOfView, qreal(w)/h, 1.0f, 10000.0f); + } + */ +} + +void OsgEarthItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *style, QWidget *widget) +{ + Q_UNUSED(painter); + Q_UNUSED(style); + QGLWidget *glWidget = qobject_cast(widget); + + if (!m_glWidget) { + //make a shared gl widget to avoid + //osg rendering to mess with qpainter state + m_glWidget = new QGLWidget(widget, glWidget); + m_glWidget.data()->setAttribute(Qt::WA_PaintOutsidePaintEvent); + } + + if (!m_viewer.get()) + QMetaObject::invokeMethod(this, "initScene", Qt::QueuedConnection); + + if (glWidget && m_fbo) + glWidget->drawTexture(boundingRect(), m_fbo->texture()); +} + +void OsgEarthItem::markCameraDirty() +{ + m_cameraDirty = true; + QMetaObject::invokeMethod(this, "updateFBO", Qt::QueuedConnection); +} + +void OsgEarthItem::updateFBO() +{ + if (!m_cameraDirty || !m_viewer.get() || m_glWidget.isNull()) + return; + + m_cameraDirty = false; + m_glWidget.data()->makeCurrent(); + + if (m_fbo && m_fbo->size() != m_currentSize) { + delete m_fbo; + m_fbo = 0; + } + + if (!m_fbo) { + m_fbo = new QGLFramebufferObject(m_currentSize, QGLFramebufferObject::CombinedDepthStencil); + QPainter p(m_fbo); + p.fillRect(0,0,m_currentSize.width(), m_currentSize.height(), Qt::gray); + } + + //To find a camera view matrix, find placer matrixes for two points + //onr at requested coords and another latitude shifted by 0.01 deg + osgEarth::Util::ObjectPlacer placer(m_viewer->getSceneData()); + + osg::Matrixd positionMatrix; + placer.createPlacerMatrix(m_latitude, m_longitude, m_altitude, positionMatrix); + osg::Matrixd positionMatrix2; + placer.createPlacerMatrix(m_latitude+0.01, m_longitude, m_altitude, positionMatrix2); + + osg::Vec3d eye(0.0f, 0.0f, 0.0f); + osg::Vec3d viewVector(0.0f, 0.0f, 0.0f); + osg::Vec3d upVector(0.0f, 0.0f, 1.0f); + + eye = positionMatrix.preMult(eye); + upVector = positionMatrix.preMult(upVector); + upVector.normalize(); + viewVector = positionMatrix2.preMult(viewVector) - eye; + viewVector.normalize(); + viewVector *= 10.0; + + //TODO: clarify the correct rotation order, + //currently assuming yaw, pitch, roll + osg::Quat q; + q.makeRotate(-m_yaw*M_PI/180.0, upVector); + upVector = q * upVector; + viewVector = q * viewVector; + + osg::Vec3d side = viewVector ^ upVector; + q.makeRotate(m_pitch*M_PI/180.0, side); + upVector = q * upVector; + viewVector = q * viewVector; + + q.makeRotate(m_roll*M_PI/180.0, viewVector); + upVector = q * upVector; + viewVector = q * viewVector; + + osg::Vec3d center = eye + viewVector; + +// qDebug() << "e " << eye.x() << eye.y() << eye.z(); +// qDebug() << "c " << center.x() << center.y() << center.z(); +// qDebug() << "up" << upVector.x() << upVector.y() << upVector.z(); + + m_viewer->getCamera()->setViewMatrixAsLookAt(osg::Vec3d(eye.x(), eye.y(), eye.z()), + osg::Vec3d(center.x(), center.y(), center.z()), + osg::Vec3d(upVector.x(), upVector.y(), upVector.z())); + + { + QPainter fboPainter(m_fbo); + fboPainter.beginNativePainting(); + m_viewer->frame(); + fboPainter.endNativePainting(); + } + m_glWidget.data()->doneCurrent(); + + update(); +} + +void OsgEarthItem::setRoll(qreal arg) +{ + if (!qFuzzyCompare(m_roll, arg)) { + m_roll = arg; + markCameraDirty(); + emit rollChanged(arg); + } +} + +void OsgEarthItem::setPitch(qreal arg) +{ + if (!qFuzzyCompare(m_pitch, arg)) { + m_pitch = arg; + markCameraDirty(); + emit pitchChanged(arg); + } +} + +void OsgEarthItem::setYaw(qreal arg) +{ + if (!qFuzzyCompare(m_yaw, arg)) { + m_yaw = arg; + markCameraDirty(); + emit yawChanged(arg); + } +} + +void OsgEarthItem::setLatitude(double arg) +{ + //not sure qFuzzyCompare is accurate enough for geo coordinates + if (m_latitude != arg) { + m_latitude = arg; + emit latitudeChanged(arg); + } +} + +void OsgEarthItem::setLongitude(double arg) +{ + if (m_longitude != arg) { + m_longitude = arg; + emit longitudeChanged(arg); + } +} + +void OsgEarthItem::setAltitude(double arg) +{ + if (!qFuzzyCompare(m_altitude,arg)) { + m_altitude = arg; + emit altitudeChanged(arg); + } +} + +//! Camera vertical field of view in degrees +void OsgEarthItem::setFieldOfView(qreal arg) +{ + if (!qFuzzyCompare(m_fieldOfView,arg)) { + m_fieldOfView = arg; + emit fieldOfViewChanged(arg); + + if (m_viewer.get()) { + m_viewer->getCamera()->setProjectionMatrixAsPerspective( + m_fieldOfView, + qreal(m_currentSize.width())/m_currentSize.height(), + 1.0f, 10000.0f); + } + + markCameraDirty(); + } +} + +void OsgEarthItem::setSceneFile(QString arg) +{ + if (m_sceneFile != arg) { + m_sceneFile = arg; + emit sceneFileChanged(arg); + } +} + + +void OsgEarthItem::initScene() +{ + if (m_viewer.get()) + return; + + int w = m_currentSize.width(); + int h = m_currentSize.height(); + + QString sceneFile = m_sceneFile; + + //try to resolve the relative scene file name: + if (!QFileInfo(sceneFile).exists()) { + QDeclarativeView *view = qobject_cast(scene()->views().first()); + + if (view) { + QUrl baseUrl = view->engine()->baseUrl(); + sceneFile = baseUrl.resolved(sceneFile).toLocalFile(); + } + } + + m_model = osgDB::readNodeFile(sceneFile.toStdString()); + + m_gw = new osgViewer::GraphicsWindowEmbedded(0,0,w,h); + + m_viewer = new osgViewer::Viewer(); + m_viewer->setThreadingModel(osgViewer::Viewer::SingleThreaded); + m_viewer->setSceneData(m_model); + m_viewer->getDatabasePager()->setDoPreCompile(true); + + osg::Camera *camera = m_viewer->getCamera(); + camera->setViewport(new osg::Viewport(0,0,w,h)); + camera->setGraphicsContext(m_gw); + camera->setClearMask(GL_COLOR_BUFFER_BIT|GL_DEPTH_BUFFER_BIT); + + // configure the near/far so we don't clip things that are up close + camera->setNearFarRatio(0.00002); + camera->setProjectionMatrixAsPerspective(m_fieldOfView, qreal(w)/h, 1.0f, 10000.0f); + + markCameraDirty(); +} + diff --git a/ground/openpilotgcs/src/plugins/pfdqml/osgearth.h b/ground/openpilotgcs/src/plugins/pfdqml/osgearth.h new file mode 100644 index 000000000..6a1095a07 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/osgearth.h @@ -0,0 +1,117 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef OSGEARTH_H +#define OSGEARTH_H + +#include + +#include +#include + +class QGLFramebufferObject; +class QGLWidget; + +class OsgEarthItem : public QDeclarativeItem +{ + Q_OBJECT + Q_DISABLE_COPY(OsgEarthItem) + + Q_PROPERTY(QString sceneFile READ sceneFile WRITE setSceneFile NOTIFY sceneFileChanged) + Q_PROPERTY(qreal fieldOfView READ fieldOfView WRITE setFieldOfView NOTIFY fieldOfViewChanged) + + Q_PROPERTY(qreal roll READ roll WRITE setRoll NOTIFY rollChanged) + Q_PROPERTY(qreal pitch READ pitch WRITE setPitch NOTIFY pitchChanged) + Q_PROPERTY(qreal yaw READ yaw WRITE setYaw NOTIFY yawChanged) + + Q_PROPERTY(double latitude READ latitude WRITE setLatitude NOTIFY latitudeChanged) + Q_PROPERTY(double longitude READ longitude WRITE setLongitude NOTIFY longitudeChanged) + Q_PROPERTY(double altitude READ altitude WRITE setAltitude NOTIFY altitudeChanged) + +public: + OsgEarthItem(QDeclarativeItem *parent = 0); + ~OsgEarthItem(); + + QString sceneFile() const { return m_sceneFile; } + qreal fieldOfView() const { return m_fieldOfView; } + + qreal roll() const { return m_roll; } + qreal pitch() const { return m_pitch; } + qreal yaw() const { return m_yaw; } + + double latitude() const { return m_latitude; } + double longitude() const { return m_longitude; } + double altitude() const { return m_altitude; } + +protected: + void geometryChanged(const QRectF &newGeometry, const QRectF &oldGeometry); + void paint(QPainter *painter, const QStyleOptionGraphicsItem *style, QWidget *widget); + +public slots: + void setSceneFile(QString arg); + void setFieldOfView(qreal arg); + + void setRoll(qreal arg); + void setPitch(qreal arg); + void setYaw(qreal arg); + + void setLatitude(double arg); + void setLongitude(double arg); + void setAltitude(double arg); + +signals: + void rollChanged(qreal arg); + void pitchChanged(qreal arg); + void yawChanged(qreal arg); + + void latitudeChanged(double arg); + void longitudeChanged(double arg); + void altitudeChanged(double arg); + + void sceneFileChanged(QString arg); + void fieldOfViewChanged(qreal arg); + +private slots: + void markCameraDirty(); + void updateFBO(); + void initScene(); + +private: + osg::ref_ptr m_viewer; + osg::ref_ptr m_gw; + osg::ref_ptr m_model; + QWeakPointer m_glWidget; + QGLFramebufferObject *m_fbo; + QSize m_currentSize; + + qreal m_roll; + qreal m_pitch; + qreal m_yaw; + + double m_latitude; + double m_longitude; + double m_altitude; + + qreal m_fieldOfView; + QString m_sceneFile; + + bool m_cameraDirty; +}; + +QML_DECLARE_TYPE(OsgEarthItem) + +#endif // OSGEARTH_H + diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro b/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro new file mode 100644 index 000000000..7064f8a0c --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro @@ -0,0 +1,35 @@ +TEMPLATE = lib +TARGET = PfdQml +QT += svg +QT += opengl +QT += declarative + +include(../../openpilotgcsplugin.pri) +include(../../plugins/coreplugin/coreplugin.pri) +include(pfdqml_dependencies.pri) + +LIBS += -losg -losgUtil -losgViewer -losgQt -losgDB -lOpenThreads -losgGA +LIBS += -losgEarth -losgEarthFeatures -losgEarthUtil + +HEADERS += \ + pfdqmlplugin.h \ + pfdqmlgadget.h \ + pfdqmlgadgetwidget.h \ + pfdqmlgadgetfactory.h \ + pfdqmlgadgetconfiguration.h \ + pfdqmlgadgetoptionspage.h \ + osgearth.h + +SOURCES += \ + pfdqmlplugin.cpp \ + pfdqmlgadget.cpp \ + pfdqmlgadgetfactory.cpp \ + pfdqmlgadgetwidget.cpp \ + pfdqmlgadgetconfiguration.cpp \ + pfdqmlgadgetoptionspage.cpp \ + osgearth.cpp + +OTHER_FILES += PfdQml.pluginspec + +FORMS += pfdqmlgadgetoptionspage.ui + diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqml_dependencies.pri b/ground/openpilotgcs/src/plugins/pfdqml/pfdqml_dependencies.pri new file mode 100644 index 000000000..9aae5fbc0 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqml_dependencies.pri @@ -0,0 +1 @@ +include(../../plugins/uavobjects/uavobjects.pri) diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp new file mode 100644 index 000000000..48661a581 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp @@ -0,0 +1,44 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pfdqmlgadget.h" +#include "pfdqmlgadgetwidget.h" +#include "pfdqmlgadgetconfiguration.h" + +PfdQmlGadget::PfdQmlGadget(QString classId, PfdQmlGadgetWidget *widget, QWidget *parent) : + IUAVGadget(classId, parent), + m_widget(widget) +{ +} + +PfdQmlGadget::~PfdQmlGadget() +{ + delete m_widget; +} + +/* + This is called when a configuration is loaded, and updates the plugin's settings. + Careful: the plugin is already drawn before the loadConfiguration method is called the + first time, so you have to be careful not to assume all the plugin values are initialized + the first time you use them + */ +void PfdQmlGadget::loadConfiguration(IUAVGadgetConfiguration* config) +{ + PfdQmlGadgetConfiguration *m = qobject_cast(config); + m_widget->setQmlFile(m->qmlFile()); + m_widget->setEarthFile(m->earthFile()); + m_widget->setTerrainEnabled(m->terrainEnabled()); +} diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.h b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.h new file mode 100644 index 000000000..073e1f326 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.h @@ -0,0 +1,45 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PFDQMLGADGET_H_ +#define PFDQMLQMLGADGET_H_ + +#include +#include "pfdqmlgadgetwidget.h" + +class IUAVGadget; +class QWidget; +class QString; +class PfdQmlGadgetWidget; + +using namespace Core; + +class PfdQmlGadget : public Core::IUAVGadget +{ + Q_OBJECT +public: + PfdQmlGadget(QString classId, PfdQmlGadgetWidget *widget, QWidget *parent = 0); + ~PfdQmlGadget(); + + QWidget *widget() { return m_widget; } + void loadConfiguration(IUAVGadgetConfiguration* config); + +private: + PfdQmlGadgetWidget *m_widget; +}; + + +#endif // PFDQMLQMLGADGET_H_ diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.cpp new file mode 100644 index 000000000..56926917e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.cpp @@ -0,0 +1,67 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pfdqmlgadgetconfiguration.h" +#include "utils/pathutils.h" + +/** + * Loads a saved configuration or defaults if non exist. + * + */ +PfdQmlGadgetConfiguration::PfdQmlGadgetConfiguration(QString classId, QSettings *qSettings, QObject *parent) : + IUAVGadgetConfiguration(classId, parent), + m_qmlFile("Unknown"), + m_earthFile("Unknown"), + m_terrainEnabled(true) +{ + //if a saved configuration exists load it + if(qSettings != 0) { + m_qmlFile = qSettings->value("qmlFile").toString(); + m_qmlFile=Utils::PathUtils().InsertDataPath(m_qmlFile); + + m_earthFile = qSettings->value("earthFile").toString(); + m_earthFile=Utils::PathUtils().InsertDataPath(m_earthFile); + + m_terrainEnabled = qSettings->value("terrainEnabled").toBool(); + } +} + +/** + * Clones a configuration. + * + */ +IUAVGadgetConfiguration *PfdQmlGadgetConfiguration::clone() +{ + PfdQmlGadgetConfiguration *m = new PfdQmlGadgetConfiguration(this->classId()); + m->m_qmlFile = m_qmlFile; + m->m_earthFile = m_earthFile; + m->m_terrainEnabled = m_terrainEnabled; + + return m; +} + +/** + * Saves a configuration. + * + */ +void PfdQmlGadgetConfiguration::saveConfig(QSettings* qSettings) const { + QString qmlFile = Utils::PathUtils().RemoveDataPath(m_qmlFile); + qSettings->setValue("qmlFile", qmlFile); + QString earthFile = Utils::PathUtils().RemoveDataPath(m_earthFile); + qSettings->setValue("earthFile", earthFile); + + qSettings->setValue("terrainEnabled", m_terrainEnabled); +} diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.h b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.h new file mode 100644 index 000000000..c9986173b --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.h @@ -0,0 +1,48 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PFDQMLGADGETCONFIGURATION_H +#define PFDQMLGADGETCONFIGURATION_H + +#include + +using namespace Core; + +class PfdQmlGadgetConfiguration : public IUAVGadgetConfiguration +{ +Q_OBJECT +public: + explicit PfdQmlGadgetConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); + + void setQmlFile(const QString &fileName) { m_qmlFile=fileName; } + void setEarthFile(const QString &fileName) { m_earthFile=fileName; } + void setTerrainEnabled(bool flag) { m_terrainEnabled = flag; } + + //get dial configuration functions + QString qmlFile() const { return m_qmlFile; } + QString earthFile() const { return m_earthFile; } + bool terrainEnabled() const { return m_terrainEnabled; } + + void saveConfig(QSettings* settings) const; + IUAVGadgetConfiguration *clone(); + +private: + QString m_qmlFile; // The name of the dial's SVG source file + QString m_earthFile; // The name of osgearth terrain file + bool m_terrainEnabled; +}; + +#endif // PfdQmlGADGETCONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetfactory.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetfactory.cpp new file mode 100644 index 000000000..9616c4796 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetfactory.cpp @@ -0,0 +1,49 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "pfdqmlgadgetfactory.h" +#include "pfdqmlgadgetwidget.h" +#include "pfdqmlgadget.h" +#include "pfdqmlgadgetconfiguration.h" +#include "pfdqmlgadgetoptionspage.h" +#include + +PfdQmlGadgetFactory::PfdQmlGadgetFactory(QObject *parent) : + IUAVGadgetFactory(QString("PfdQmlGadget"), + tr("PFD (qml)"), + parent) +{ +} + +PfdQmlGadgetFactory::~PfdQmlGadgetFactory() +{ +} + +Core::IUAVGadget* PfdQmlGadgetFactory::createGadget(QWidget *parent) +{ + PfdQmlGadgetWidget* gadgetWidget = new PfdQmlGadgetWidget(parent); + return new PfdQmlGadget(QString("PfdQmlGadget"), gadgetWidget, parent); +} + +IUAVGadgetConfiguration *PfdQmlGadgetFactory::createConfiguration(QSettings *qSettings) +{ + return new PfdQmlGadgetConfiguration(QString("PfdQmlGadget"), qSettings); +} + +IOptionsPage *PfdQmlGadgetFactory::createOptionsPage(IUAVGadgetConfiguration *config) +{ + return new PfdQmlGadgetOptionsPage(qobject_cast(config)); +} + diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetfactory.h b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetfactory.h new file mode 100644 index 000000000..950124010 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetfactory.h @@ -0,0 +1,41 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PFDQMLGADGETFACTORY_H_ +#define PFDQMLGADGETFACTORY_H_ + +#include + +namespace Core { +class IUAVGadget; +class IUAVGadgetFactory; +} + +using namespace Core; + +class PfdQmlGadgetFactory : public IUAVGadgetFactory +{ + Q_OBJECT +public: + PfdQmlGadgetFactory(QObject *parent = 0); + ~PfdQmlGadgetFactory(); + + Core::IUAVGadget *createGadget(QWidget *parent); + IUAVGadgetConfiguration *createConfiguration(QSettings *qSettings); + IOptionsPage *createOptionsPage(IUAVGadgetConfiguration *config); +}; + +#endif // PfdQmlGADGETFACTORY_H_ diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp new file mode 100644 index 000000000..01ee89c96 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp @@ -0,0 +1,77 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pfdqmlgadgetoptionspage.h" +#include "pfdqmlgadgetconfiguration.h" +#include "ui_pfdqmlgadgetoptionspage.h" +#include "extensionsystem/pluginmanager.h" +#include "uavobjectmanager.h" +#include "uavdataobject.h" + + +#include +#include +#include + +PfdQmlGadgetOptionsPage::PfdQmlGadgetOptionsPage(PfdQmlGadgetConfiguration *config, QObject *parent) : + IOptionsPage(parent), + m_config(config) +{ +} + +//creates options page widget (uses the UI file) +QWidget *PfdQmlGadgetOptionsPage::createPage(QWidget *parent) +{ + + options_page = new Ui::PfdQmlGadgetOptionsPage(); + //main widget + QWidget *optionsPageWidget = new QWidget; + //main layout + options_page->setupUi(optionsPageWidget); + + // Restore the contents from the settings: + options_page->qmlSourceFile->setExpectedKind(Utils::PathChooser::File); + options_page->qmlSourceFile->setPromptDialogFilter(tr("QML file (*.qml)")); + options_page->qmlSourceFile->setPromptDialogTitle(tr("Choose QML file")); + options_page->qmlSourceFile->setPath(m_config->qmlFile()); + + // Restore the contents from the settings: + options_page->earthFile->setExpectedKind(Utils::PathChooser::File); + options_page->earthFile->setPromptDialogFilter(tr("OsgEarth (*.earth)")); + options_page->earthFile->setPromptDialogTitle(tr("Choose OsgEarth terrain file")); + options_page->earthFile->setPath(m_config->earthFile()); + + options_page->showTerrain->setChecked(m_config->terrainEnabled()); + + return optionsPageWidget; +} + +/** + * Called when the user presses apply or OK. + * + * Saves the current values + * + */ +void PfdQmlGadgetOptionsPage::apply() +{ + m_config->setQmlFile(options_page->qmlSourceFile->path()); + m_config->setEarthFile(options_page->earthFile->path()); + m_config->setTerrainEnabled(options_page->showTerrain->isChecked()); +} + +void PfdQmlGadgetOptionsPage::finish() +{ +} diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.h b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.h new file mode 100644 index 000000000..8797275a6 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.h @@ -0,0 +1,54 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PFDQMLGADGETOPTIONSPAGE_H +#define PFDQMLGADGETOPTIONSPAGE_H + +#include "coreplugin/dialogs/ioptionspage.h" +#include "QString" +#include +#include + +namespace Core { +class IUAVGadgetConfiguration; +} + +class PfdQmlGadgetConfiguration; + +namespace Ui { + class PfdQmlGadgetOptionsPage; +} + +using namespace Core; + +class PfdQmlGadgetOptionsPage : public IOptionsPage +{ +Q_OBJECT +public: + explicit PfdQmlGadgetOptionsPage(PfdQmlGadgetConfiguration *config, QObject *parent = 0); + + QWidget *createPage(QWidget *parent); + void apply(); + void finish(); + +private: + Ui::PfdQmlGadgetOptionsPage *options_page; + PfdQmlGadgetConfiguration *m_config; + +private slots: +}; + +#endif // PfdQmlGADGETOPTIONSPAGE_H diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui new file mode 100644 index 000000000..dd8d03e4f --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui @@ -0,0 +1,135 @@ + + + PfdQmlGadgetOptionsPage + + + + 0 + 0 + 441 + 339 + + + + + 0 + 0 + + + + Form + + + + + + 10 + + + QLayout::SetMaximumSize + + + 10 + + + + + QML file: + + + + + + + + 0 + 0 + + + + + + + + + + Qt::Horizontal + + + + + + + + + true + + + Show terrain + + + true + + + + + + + + + 10 + + + QLayout::SetMaximumSize + + + 10 + + + + + OsgEarth file: + + + + + + + + 0 + 0 + + + + + + + + + + Qt::Vertical + + + QSizePolicy::MinimumExpanding + + + + 20 + 40 + + + + + + + + + Utils::PathChooser + QWidget +

utils/pathchooser.h
+ 1 +
+
+ + + diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp new file mode 100644 index 000000000..ac2d7ada2 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp @@ -0,0 +1,106 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pfdqmlgadgetwidget.h" +#include "extensionsystem/pluginmanager.h" +#include "uavobjectmanager.h" +#include "uavobject.h" +#include "utils/svgimageprovider.h" +#include "osgearth.h" + +#include +#include +#include +#include +#include + +#include +#include +#include + +PfdQmlGadgetWidget::PfdQmlGadgetWidget(QWidget *parent) : + QDeclarativeView(parent) +{ + setMinimumSize(64,64); + setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); + setResizeMode(SizeRootObjectToView); + + setViewport(new QGLWidget(QGLFormat(QGL::SampleBuffers))); + + QStringList objectsToExport; + objectsToExport << "VelocityActual" << + "PositionActual" << + "AttitudeActual" << + "GPSPosition" << + "GCSTelemetryStats" << + "FlightBatteryState"; + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *objManager = pm->getObject(); + + foreach (const QString &objectName, objectsToExport) { + UAVObject* object = objManager->getObject(objectName); + if (object) + engine()->rootContext()->setContextProperty(objectName, object); + else + qWarning() << "Failed to load object" << objectName; + } + + //to expose settings values + engine()->rootContext()->setContextProperty("qmlWidget", this); + + qmlRegisterType("org.OpenPilot", 1, 0, "OsgEarth"); +} + +PfdQmlGadgetWidget::~PfdQmlGadgetWidget() +{ +} + +void PfdQmlGadgetWidget::setQmlFile(QString fn) +{ + m_qmlFileName = fn; + + engine()->removeImageProvider("svg"); + SvgImageProvider *svgProvider = new SvgImageProvider(fn); + engine()->addImageProvider("svg", svgProvider); + + //it's necessary to allow qml side to query svg element position + engine()->rootContext()->setContextProperty("svgRenderer", svgProvider); + engine()->setBaseUrl(QUrl::fromLocalFile(fn)); + + qDebug() << Q_FUNC_INFO << fn; + setSource(QUrl::fromLocalFile(fn)); + + foreach(const QDeclarativeError &error, errors()) { + qDebug() << error.description(); + } +} + +void PfdQmlGadgetWidget::setEarthFile(QString arg) +{ + if (m_earthFile != arg) { + m_earthFile = arg; + emit earthFileChanged(arg); + } +} + +void PfdQmlGadgetWidget::setTerrainEnabled(bool arg) +{ + if (m_terrainEnabled != arg) { + m_terrainEnabled = arg; + emit terrainEnabledChanged(arg); + } +} diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.h b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.h new file mode 100644 index 000000000..6e0f8b35f --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.h @@ -0,0 +1,51 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PFDQMLGADGETWIDGET_H_ +#define PFDQMLGADGETWIDGET_H_ + +#include "pfdqmlgadgetconfiguration.h" +#include + +class PfdQmlGadgetWidget : public QDeclarativeView +{ + Q_OBJECT + Q_PROPERTY(QString earthFile READ earthFile WRITE setEarthFile NOTIFY earthFileChanged) + Q_PROPERTY(bool terrainEnabled READ terrainEnabled WRITE setTerrainEnabled NOTIFY terrainEnabledChanged) + +public: + PfdQmlGadgetWidget(QWidget *parent = 0); + ~PfdQmlGadgetWidget(); + void setQmlFile(QString fn); + + QString earthFile() const { return m_earthFile; } + bool terrainEnabled() const { return m_terrainEnabled; } + +public slots: + void setEarthFile(QString arg); + void setTerrainEnabled(bool arg); + +signals: + void earthFileChanged(QString arg); + void terrainEnabledChanged(bool arg); + +private: + QString m_qmlFileName; + QString m_earthFile; + bool m_terrainEnabled; +}; + +#endif /* PFDQMLGADGETWIDGET_H_ */ diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlplugin.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlplugin.cpp new file mode 100644 index 000000000..f7d40a24d --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlplugin.cpp @@ -0,0 +1,55 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pfdqmlplugin.h" +#include "pfdqmlgadgetfactory.h" +#include +#include +#include +#include + + +PfdQmlPlugin::PfdQmlPlugin() +{ + // Do nothing +} + +PfdQmlPlugin::~PfdQmlPlugin() +{ + // Do nothing +} + +bool PfdQmlPlugin::initialize(const QStringList& args, QString *errMsg) +{ + Q_UNUSED(args); + Q_UNUSED(errMsg); + mf = new PfdQmlGadgetFactory(this); + addAutoReleasedObject(mf); + + return true; +} + +void PfdQmlPlugin::extensionsInitialized() +{ + // Do nothing +} + +void PfdQmlPlugin::shutdown() +{ + // Do nothing +} +Q_EXPORT_PLUGIN(PfdQmlPlugin) + diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlplugin.h b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlplugin.h new file mode 100644 index 000000000..e1ef1a122 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlplugin.h @@ -0,0 +1,36 @@ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PFDQMLPLUGIN_H_ +#define PFDQMLPLUGIN_H_ + +#include + +class PfdQmlGadgetFactory; + +class PfdQmlPlugin : public ExtensionSystem::IPlugin +{ +public: + PfdQmlPlugin(); + ~PfdQmlPlugin(); + + void extensionsInitialized(); + bool initialize(const QStringList &arguments, QString *errorString); + void shutdown(); +private: + PfdQmlGadgetFactory *mf; +}; +#endif /* PFDQMLPLUGIN_H_ */ diff --git a/ground/openpilotgcs/src/plugins/plugins.pro b/ground/openpilotgcs/src/plugins/plugins.pro index 154335e3a..63fd4c297 100644 --- a/ground/openpilotgcs/src/plugins/plugins.pro +++ b/ground/openpilotgcs/src/plugins/plugins.pro @@ -128,12 +128,17 @@ plugin_pfd.depends = plugin_coreplugin plugin_pfd.depends += plugin_uavobjects SUBDIRS += plugin_pfd -# Primary Flight Display (PFD) gadget +# QML viewer gadget plugin_qmlview.subdir = qmlview plugin_qmlview.depends = plugin_coreplugin plugin_qmlview.depends += plugin_uavobjects SUBDIRS += plugin_qmlview +# Primary Flight Display (PFD) gadget, QML version +plugin_pfdqml.subdir = pfdqml +plugin_pfdqml.depends = plugin_coreplugin +plugin_pfdqml.depends += plugin_uavobjects +SUBDIRS += plugin_pfdqml #IP connection plugin plugin_ipconnection.subdir = ipconnection From 717b0d4561a06df9f9282a71aca78878d49c5c44 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Tue, 24 Jul 2012 22:10:17 +0100 Subject: [PATCH 063/543] Revert "OP-39 Added some pages and some functionality to the OP SetupWizard." This reverts commit ebe76e4ae65f7b4b94f705e7a418699936186494. --- .../plugins/coreplugin/connectionmanager.cpp | 143 ++++++----- .../plugins/coreplugin/connectionmanager.h | 32 +-- .../setupwizard/pages/abstractwizardpage.cpp | 35 --- .../setupwizard/pages/abstractwizardpage.h | 48 ---- .../setupwizard/pages/controllerpage.cpp | 225 ------------------ .../setupwizard/pages/controllerpage.h | 67 ------ .../setupwizard/pages/controllerpage.ui | 163 ------------- .../src/plugins/setupwizard/pages/endpage.cpp | 30 +-- .../src/plugins/setupwizard/pages/endpage.h | 33 +-- .../src/plugins/setupwizard/pages/endpage.ui | 2 +- .../setupwizard/pages/fixedwingpage.cpp | 42 ---- .../plugins/setupwizard/pages/fixedwingpage.h | 49 ---- .../setupwizard/pages/fixedwingpage.ui | 43 ---- .../plugins/setupwizard/pages/helipage.cpp | 42 ---- .../src/plugins/setupwizard/pages/helipage.h | 49 ---- .../src/plugins/setupwizard/pages/helipage.ui | 43 ---- .../plugins/setupwizard/pages/multipage.cpp | 125 ---------- .../src/plugins/setupwizard/pages/multipage.h | 59 ----- .../plugins/setupwizard/pages/multipage.ui | 146 ------------ .../pages/notyetimplementedpage.cpp | 42 ---- .../setupwizard/pages/notyetimplementedpage.h | 49 ---- .../pages/notyetimplementedpage.ui | 43 ---- .../plugins/setupwizard/pages/startpage.cpp | 30 +-- .../src/plugins/setupwizard/pages/startpage.h | 32 +-- .../plugins/setupwizard/pages/surfacepage.cpp | 42 ---- .../plugins/setupwizard/pages/surfacepage.h | 49 ---- .../plugins/setupwizard/pages/surfacepage.ui | 43 ---- .../plugins/setupwizard/pages/vehiclepage.cpp | 61 ----- .../plugins/setupwizard/pages/vehiclepage.h | 50 ---- .../plugins/setupwizard/pages/vehiclepage.ui | 168 ------------- .../src/plugins/setupwizard/setupwizard.cpp | 59 +---- .../src/plugins/setupwizard/setupwizard.h | 20 +- .../src/plugins/setupwizard/setupwizard.pro | 36 +-- .../plugins/setupwizard/setupwizardplugin.cpp | 4 +- .../plugins/setupwizard/setupwizardplugin.h | 4 +- .../plugins/setupwizard/wizardResources.qrc | 3 - 36 files changed, 109 insertions(+), 2002 deletions(-) delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.cpp delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.h delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.cpp delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.h delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.cpp delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.h delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.ui delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.cpp delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.h delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.ui delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.cpp delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.h delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.ui delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp index 5fa2ead50..f49d98c0e 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp @@ -44,15 +44,15 @@ namespace Core { ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow, QTabWidget *modeStack) : - QWidget(mainWindow), // Pip - m_availableDevList(0), + QWidget(mainWindow), // Pip + m_availableDevList(0), m_connectBtn(0), - m_ioDev(NULL), - m_mainWindow(mainWindow) + m_ioDev(NULL), + m_mainWindow(mainWindow) { - // Q_UNUSED(mainWindow); + // Q_UNUSED(mainWindow); - /* QVBoxLayout *top = new QVBoxLayout; +/* QVBoxLayout *top = new QVBoxLayout; top->setSpacing(0); top->setMargin(0);*/ @@ -72,7 +72,7 @@ ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow, QTabWidge m_connectBtn->setEnabled(false); layout->addWidget(m_connectBtn); - /* Utils::StyledBar *bar = new Utils::StyledBar; +/* Utils::StyledBar *bar = new Utils::StyledBar; bar->setLayout(layout); top->addWidget(bar);*/ @@ -81,29 +81,33 @@ ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow, QTabWidge // modeStack->insertCornerWidget(modeStack->cornerWidgetCount()-1, this); modeStack->setCornerWidget(this, Qt::TopRightCorner); - QObject::connect(m_connectBtn, SIGNAL(pressed()), this, SLOT(onConnectPressed())); + QObject::connect(m_connectBtn, SIGNAL(pressed()), this, SLOT(onConnectPressed())); } ConnectionManager::~ConnectionManager() { - disconnectDevice(); // Pip - suspendPolling(); // Pip + disconnectDevice(); // Pip + suspendPolling(); // Pip } void ConnectionManager::init() { //register to the plugin manager so we can receive //new connection object from plugins - QObject::connect(ExtensionSystem::PluginManager::instance(), SIGNAL(objectAdded(QObject*)), this, SLOT(objectAdded(QObject*))); - QObject::connect(ExtensionSystem::PluginManager::instance(), SIGNAL(aboutToRemoveObject(QObject*)), this, SLOT(aboutToRemoveObject(QObject*))); + QObject::connect(ExtensionSystem::PluginManager::instance(), SIGNAL(objectAdded(QObject*)), this, SLOT(objectAdded(QObject*))); + QObject::connect(ExtensionSystem::PluginManager::instance(), SIGNAL(aboutToRemoveObject(QObject*)), this, SLOT(aboutToRemoveObject(QObject*))); } /** * Method called when the user clicks the "Connect" button */ -bool ConnectionManager::connectDevice(devListItem device) +bool ConnectionManager::connectDevice() { - QIODevice *io_dev = device.connection->openDevice(device.Name); + devListItem connection_device = findDevice(m_availableDevList->itemData(m_availableDevList->currentIndex(),Qt::ToolTipRole).toString()); + if (!connection_device.connection) + return false; + + QIODevice *io_dev = connection_device.connection->openDevice(connection_device.Name); if (!io_dev) return false; @@ -111,23 +115,23 @@ bool ConnectionManager::connectDevice(devListItem device) // check if opening the device worked if (!io_dev->isOpen()) { - qDebug() << "Error: io_dev->isOpen() returned FALSE .. could not open connection to " << device.devName + qDebug() << "Error: io_dev->isOpen() returned FALSE .. could not open connection to " << connection_device.devName << ": " << io_dev->errorString(); // close the device // EDOUARD: why do we close if we could not open ??? try { - device.connection->closeDevice(device.devName); + connection_device.connection->closeDevice(connection_device.devName); } catch (...) { // handle exception - qDebug() << "Exception: connection_device.connection->closeDevice(" << device.devName << ")"; + qDebug() << "Exception: connection_device.connection->closeDevice(" << connection_device.devName << ")"; } return false; } // we appear to have connected to the device OK // remember the connection/device details - m_connectionDevice = device; + m_connectionDevice = connection_device; m_ioDev = io_dev; connect(m_connectionDevice.connection, SIGNAL(destroyed(QObject *)), this, SLOT(onConnectionDestroyed(QObject *)), Qt::QueuedConnection); @@ -167,8 +171,6 @@ bool ConnectionManager::disconnectDevice() m_connectionDevice.connection = NULL; m_ioDev = NULL; - emit deviceDisconnected(); - m_connectBtn->setText("Connect"); m_availableDevList->setEnabled(true); @@ -182,7 +184,7 @@ void ConnectionManager::objectAdded(QObject *obj) { //Check if a plugin added a connection object to the pool IConnection *connection = Aggregation::query(obj); - if (!connection) return; + if (!connection) return; //qDebug() << "Connection object registered:" << connection->connectionName(); //qDebug() << connection->availableDevices(); @@ -194,23 +196,23 @@ void ConnectionManager::objectAdded(QObject *obj) // to do things m_connectionsList.append(connection); - QObject::connect(connection, SIGNAL(availableDevChanged(IConnection *)), this, SLOT(devChanged(IConnection *))); + QObject::connect(connection, SIGNAL(availableDevChanged(IConnection *)), this, SLOT(devChanged(IConnection *))); } void ConnectionManager::aboutToRemoveObject(QObject *obj) { //Check if a plugin added a connection object to the pool IConnection *connection = Aggregation::query(obj); - if (!connection) return; + if (!connection) return; - if (m_connectionDevice.connection && m_connectionDevice.connection == connection) // Pip - { // we are currently using the one that is about to be removed - m_connectionDevice.connection = NULL; - m_ioDev = NULL; - } + if (m_connectionDevice.connection && m_connectionDevice.connection == connection) // Pip + { // we are currently using the one that is about to be removed + m_connectionDevice.connection = NULL; + m_ioDev = NULL; + } - if (m_connectionsList.contains(connection)) - m_connectionsList.removeAt(m_connectionsList.indexOf(connection)); + if (m_connectionsList.contains(connection)) + m_connectionsList.removeAt(m_connectionsList.indexOf(connection)); } @@ -228,11 +230,8 @@ void ConnectionManager::onConnectPressed() { // Check if we have a ioDev already created: if (!m_ioDev) - { - // connecting to currently selected device - devListItem device = findDevice(m_availableDevList->itemData(m_availableDevList->currentIndex(), Qt::ToolTipRole).toString()); - if (device.connection) - connectDevice(device); + { // connecting + connectDevice(); } else { // disconnecting @@ -245,9 +244,9 @@ void ConnectionManager::onConnectPressed() */ devListItem ConnectionManager::findDevice(const QString &devName) { - foreach (devListItem d, m_devList) + foreach (devListItem d, m_devList) { - if (d.devName == devName) + if (d.devName == devName) return d; } @@ -265,13 +264,13 @@ devListItem ConnectionManager::findDevice(const QString &devName) */ void ConnectionManager::suspendPolling() { - foreach (IConnection *cnx, m_connectionsList) - { + foreach (IConnection *cnx, m_connectionsList) + { cnx->suspendPolling(); } - m_connectBtn->setEnabled(false); - m_availableDevList->setEnabled(false); + m_connectBtn->setEnabled(false); + m_availableDevList->setEnabled(false); } /** @@ -280,13 +279,13 @@ void ConnectionManager::suspendPolling() */ void ConnectionManager::resumePolling() { - foreach (IConnection *cnx, m_connectionsList) - { + foreach (IConnection *cnx, m_connectionsList) + { cnx->resumePolling(); } - m_connectBtn->setEnabled(true); - m_availableDevList->setEnabled(true); + m_connectBtn->setEnabled(true); + m_availableDevList->setEnabled(true); } /** @@ -295,21 +294,21 @@ void ConnectionManager::resumePolling() */ void ConnectionManager::unregisterAll(IConnection *connection) { - for (QLinkedList::iterator iter = m_devList.begin(); iter != m_devList.end(); ) - { - if (iter->connection == connection) - { - if (m_connectionDevice.connection && m_connectionDevice.connection == connection) - { // we are currently using the one we are about to erase - //onConnectionClosed(m_connectionDevice.connection); - disconnectDevice(); - } + for (QLinkedList::iterator iter = m_devList.begin(); iter != m_devList.end(); ) + { + if (iter->connection == connection) + { + if (m_connectionDevice.connection && m_connectionDevice.connection == connection) + { // we are currently using the one we are about to erase + //onConnectionClosed(m_connectionDevice.connection); + disconnectDevice(); + } - iter = m_devList.erase(iter); - } - else - ++iter; - } + iter = m_devList.erase(iter); + } + else + ++iter; + } } /** @@ -348,7 +347,7 @@ void ConnectionManager::devChanged(IConnection *connection) unregisterAll(connection); //and add them back in the list - QList availableDev = connection->availableDevices(); + QList availableDev = connection->availableDevices(); foreach (IConnection::device dev, availableDev) { QString cbName = connection->shortName() + ": " + dev.name; @@ -356,35 +355,32 @@ void ConnectionManager::devChanged(IConnection *connection) registerDevice(connection,cbName,dev.name,disp); } - qDebug() << "# devices " << m_devList.count(); - emit availableDevicesChanged(m_devList); - //add all the list again to the combobox - foreach (devListItem device, m_devList) + foreach (devListItem d, m_devList) { - m_availableDevList->addItem(device.displayName); - m_availableDevList->setItemData(m_availableDevList->count() - 1, (const QString)device.devName,Qt::ToolTipRole); - if(!m_ioDev && device.displayName.startsWith("USB")) + m_availableDevList->addItem(d.displayName); + m_availableDevList->setItemData(m_availableDevList->count()-1,(const QString)d.devName,Qt::ToolTipRole); + if(!m_ioDev && d.displayName.startsWith("USB")) { if(m_mainWindow->generalSettings()->autoConnect() || m_mainWindow->generalSettings()->autoSelect()) - m_availableDevList->setCurrentIndex(m_availableDevList->count() - 1); - + m_availableDevList->setCurrentIndex(m_availableDevList->count()-1); if(m_mainWindow->generalSettings()->autoConnect()) { - connectDevice(device); - qDebug() << "ConnectionManager::devChanged autoconnected USB device"; + connectDevice(); + qDebug()<<"ConnectionManager::devChanged autoconnected USB device"; } } } if(m_ioDev)//if a device is connected make it the one selected on the dropbox { - for(int x=0; x < m_availableDevList->count(); ++x) + for(int x=0;xcount();++x) { if(m_connectionDevice.devName==m_availableDevList->itemData(x,Qt::ToolTipRole).toString()) m_availableDevList->setCurrentIndex(x); } } + //disable connection button if the liNameif (m_availableDevList->count() > 0) if (m_availableDevList->count() > 0) m_connectBtn->setEnabled(true); @@ -392,7 +388,7 @@ void ConnectionManager::devChanged(IConnection *connection) m_connectBtn->setEnabled(false); } - +} void Core::ConnectionManager::connectionsCallBack() { @@ -402,5 +398,4 @@ void Core::ConnectionManager::connectionsCallBack() } connectionBackup.clear(); disconnect(ExtensionSystem::PluginManager::instance(),SIGNAL(pluginsLoadEnded()),this,SLOT(connectionsCallBack())); -} } //namespace Core diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h index 4d57319ae..289e65590 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h @@ -46,12 +46,12 @@ QT_END_NAMESPACE namespace Core { -class IConnection; + class IConnection; namespace Internal { -class FancyTabWidget; -class FancyActionBar; -class MainWindow; + class FancyTabWidget; + class FancyActionBar; + class MainWindow; } // namespace Internal @@ -75,28 +75,19 @@ public: void init(); QIODevice* getCurrentConnection() { return m_ioDev; } - devListItem getCurrentDevice() { return m_connectionDevice; } - devListItem findDevice(const QString &devName); - - QLinkedList getAvailableDevices() { return m_devList; } - - bool isConnected() { return m_ioDev != 0; } - - bool connectDevice(devListItem device); + devListItem getCurrentDevice() { return m_connectionDevice;} bool disconnectDevice(); - void suspendPolling(); void resumePolling(); protected: void unregisterAll(IConnection *connection); void registerDevice(IConnection *conn, const QString &devN, const QString &name, const QString &disp); + devListItem findDevice(const QString &devName); signals: void deviceConnected(QIODevice *dev); - void deviceDisconnected(); void deviceAboutToDisconnect(); - void availableDevicesChanged(const QLinkedList devices); private slots: void objectAdded(QObject *obj); @@ -105,9 +96,9 @@ private slots: void onConnectPressed(); void devChanged(IConnection *connection); - // void onConnectionClosed(QObject *obj); - void onConnectionDestroyed(QObject *obj); - void connectionsCallBack(); //used to call devChange after all the plugins are loaded +// void onConnectionClosed(QObject *obj); + void onConnectionDestroyed(QObject *obj); + void connectionsCallBack(); //used to call devChange after all the plugins are loaded protected: QComboBox *m_availableDevList; QPushButton *m_connectBtn; @@ -121,8 +112,9 @@ protected: QIODevice *m_ioDev; private: - Internal::MainWindow *m_mainWindow; - QList connectionBackup; + bool connectDevice(); + Internal::MainWindow *m_mainWindow; + QList connectionBackup; }; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.cpp deleted file mode 100644 index 31425fc34..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.cpp +++ /dev/null @@ -1,35 +0,0 @@ -/** - ****************************************************************************** - * - * @file abstractwizardpage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup AbstractWizardPage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "abstractwizardpage.h" - -AbstractWizardPage::AbstractWizardPage(SetupWizard* wizard, QWidget *parent) : - QWizardPage(parent) -{ - m_wizard = wizard; - setFixedSize(600, 400); -} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.h deleted file mode 100644 index 072d619e7..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.h +++ /dev/null @@ -1,48 +0,0 @@ -/** - ****************************************************************************** - * - * @file abstractwizardpage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup AbstractWizardPage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef ABSTRACTWIZARDPAGE_H -#define ABSTRACTWIZARDPAGE_H - -#include -#include "setupwizard.h" - -class AbstractWizardPage : public QWizardPage -{ - Q_OBJECT -protected: - explicit AbstractWizardPage(SetupWizard *wizard, QWidget *parent = 0); - -private: - SetupWizard *m_wizard; - -public: - SetupWizard* getWizard() { return m_wizard; } - -}; - -#endif // ABSTRACTWIZARDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.cpp deleted file mode 100644 index 7d66957d9..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.cpp +++ /dev/null @@ -1,225 +0,0 @@ -/** - ****************************************************************************** - * - * @file controllerpage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup ControllerPage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "controllerpage.h" -#include "ui_controllerpage.h" -#include "setupwizard.h" - -#include -#include - -ControllerPage::ControllerPage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), - ui(new Ui::ControllerPage) -{ - ui->setupUi(this); - - m_connectionManager = Core::ICore::instance()->connectionManager(); - Q_ASSERT(m_connectionManager); - connect(m_connectionManager, SIGNAL(availableDevicesChanged(QLinkedList)), this, SLOT(devicesChanged(QLinkedList))); - - connect(m_connectionManager, SIGNAL(deviceConnected(QIODevice*)), this, SLOT(connectionStatusChanged())); - connect(m_connectionManager, SIGNAL(deviceDisconnected()), this, SLOT(connectionStatusChanged())); - - connect(ui->manualCB, SIGNAL(toggled(bool)), this, SLOT(identificationModeChanged())); - connect(ui->connectButton, SIGNAL(clicked()), this, SLOT(connectDisconnect())); - - setupBoardTypes(); - setupDeviceList(); -} - -ControllerPage::~ControllerPage() -{ - delete ui; -} - -void ControllerPage::initializePage() -{ - if(anyControllerConnected()) { - SetupWizard::CONTROLLER_TYPE type = getControllerType(); - setControllerType(type); - } - else { - setControllerType(SetupWizard::CONTROLLER_UNKNOWN); - } - emit completeChanged(); -} - -bool ControllerPage::isComplete() const -{ - return (ui->manualCB->isChecked() && ui->boardTypeCombo->currentIndex() > 0) || - (!ui->manualCB->isChecked() && m_connectionManager->isConnected() && ui->boardTypeCombo->currentIndex() > 0); -} - -bool ControllerPage::validatePage() -{ - getWizard()->setControllerType((SetupWizard::CONTROLLER_TYPE)ui->boardTypeCombo->itemData(ui->boardTypeCombo->currentIndex()).toInt()); - return true; -} - -bool ControllerPage::anyControllerConnected() -{ - return m_connectionManager->isConnected(); -} - -SetupWizard::CONTROLLER_TYPE ControllerPage::getControllerType() -{ - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectUtilManager* utilMngr = pm->getObject(); - int id = utilMngr->getBoardModel(); - - switch (id) { - case 0x0301: - return SetupWizard::CONTROLLER_PIPX; - case 0x0401: - return SetupWizard::CONTROLLER_CC; - case 0x0402: - return SetupWizard::CONTROLLER_CC3D; - case 0x0901: - return SetupWizard::CONTROLLER_REVO; - default: - return SetupWizard::CONTROLLER_UNKNOWN; - } -} - -void ControllerPage::setupDeviceList() -{ - devicesChanged(m_connectionManager->getAvailableDevices()); - connectionStatusChanged(); -} - -void ControllerPage::setupBoardTypes() -{ - QVariant v(0); - ui->boardTypeCombo->addItem("", SetupWizard::CONTROLLER_UNKNOWN); - ui->boardTypeCombo->addItem("OpenPilot CopterControl (CC)", SetupWizard::CONTROLLER_CC); - ui->boardTypeCombo->addItem("OpenPilot CopterControl (CC3D)", SetupWizard::CONTROLLER_CC3D); - ui->boardTypeCombo->addItem("OpenPilot Revolution", SetupWizard::CONTROLLER_REVO); - ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(ui->boardTypeCombo->count() - 1, 0), v, Qt::UserRole - 1); - ui->boardTypeCombo->addItem("OP PipX Modem", SetupWizard::CONTROLLER_PIPX); - ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(ui->boardTypeCombo->count() - 1, 0), v, Qt::UserRole - 1); -} - -void ControllerPage::setControllerType(SetupWizard::CONTROLLER_TYPE type) -{ - for(int i = 0; i < ui->boardTypeCombo->count(); ++i) { - if(ui->boardTypeCombo->itemData(i) == type) { - ui->boardTypeCombo->setCurrentIndex(i); - break; - } - } -} - -void ControllerPage::devicesChanged(QLinkedList devices) -{ - // Get the selected item before the update if any - QString currSelectedDeviceName = ui->deviceCombo->currentIndex() != -1 ? - ui->deviceCombo->itemData(ui->deviceCombo->currentIndex(), Qt::ToolTipRole).toString() : ""; - - // Clear the box - ui->deviceCombo->clear(); - - int indexOfSelectedItem = -1; - int i = 0; - - // Loop and fill the combo with items from connectionmanager - foreach (Core::devListItem device, devices) - { - ui->deviceCombo->addItem(device.displayName); - QString deviceName = (const QString)device.devName; - ui->deviceCombo->setItemData(ui->deviceCombo->count() - 1, deviceName, Qt::ToolTipRole); - if(currSelectedDeviceName != "" && currSelectedDeviceName == deviceName) { - indexOfSelectedItem = i; - } - i++; - } - - // Re select the item that was selected before if any - if(indexOfSelectedItem != -1) { - ui->deviceCombo->setCurrentIndex(indexOfSelectedItem); - } - connectionStatusChanged(); -} - -void ControllerPage::connectionStatusChanged() -{ - if(m_connectionManager->isConnected()) { - ui->deviceCombo->setEnabled(false); - ui->connectButton->setText(tr("Disconnect")); - ui->boardTypeCombo->setEnabled(false); - ui->manualCB->setEnabled(false); - QString connectedDeviceName = m_connectionManager->getCurrentDevice().devName; - for(int i = 0; i < ui->deviceCombo->count(); ++i) { - if(connectedDeviceName == ui->deviceCombo->itemData(i, Qt::ToolTipRole).toString()) { - ui->deviceCombo->setCurrentIndex(i); - break; - } - } - - SetupWizard::CONTROLLER_TYPE type = getControllerType(); - setControllerType(type); - } - else { - ui->deviceCombo->setEnabled(true); - ui->connectButton->setText(tr("Connect")); - ui->boardTypeCombo->setEnabled(false); - ui->manualCB->setEnabled(true); - ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(0, 0), QVariant(0), Qt::UserRole - 1); - setControllerType(SetupWizard::CONTROLLER_UNKNOWN); - } - emit completeChanged(); -} - -void ControllerPage::identificationModeChanged() -{ - if(ui->manualCB->isChecked()) { - ui->deviceCombo->setEnabled(false); - ui->boardTypeCombo->setEnabled(true); - ui->connectButton->setEnabled(false); - ui->boardTypeCombo->setCurrentIndex(1); - ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(0, 0), QVariant(0), Qt::UserRole - 1); - } - else { - ui->connectButton->setEnabled(ui->deviceCombo->count() > 0); - ui->deviceCombo->setEnabled(!m_connectionManager->isConnected()); - ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(0, 0), QVariant(1), Qt::UserRole - 1); - ui->boardTypeCombo->setCurrentIndex(0); - ui->boardTypeCombo->setEnabled(false); - } - emit completeChanged(); -} - -void ControllerPage::connectDisconnect() -{ - if(m_connectionManager->isConnected()) { - m_connectionManager->disconnectDevice(); - } - else { - m_connectionManager->connectDevice(m_connectionManager->findDevice(ui->deviceCombo->itemData(ui->deviceCombo->currentIndex(), Qt::ToolTipRole).toString())); - } - emit completeChanged(); -} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.h deleted file mode 100644 index b9b8ae111..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.h +++ /dev/null @@ -1,67 +0,0 @@ -/** - ****************************************************************************** - * - * @file controllerpage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup ControllerPage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef CONTROLLERPAGE_H -#define CONTROLLERPAGE_H - -#include -#include -#include "setupwizard.h" -#include "abstractwizardpage.h" - -namespace Ui { -class ControllerPage; -} - -class ControllerPage : public AbstractWizardPage -{ - Q_OBJECT - -public: - explicit ControllerPage(SetupWizard *wizard, QWidget *parent = 0); - ~ControllerPage(); - void initializePage(); - bool isComplete() const; - bool validatePage(); - -private: - Ui::ControllerPage *ui; - bool anyControllerConnected(); - SetupWizard::CONTROLLER_TYPE getControllerType(); - void setupDeviceList(); - void setupBoardTypes(); - void setControllerType(SetupWizard::CONTROLLER_TYPE type); - Core::ConnectionManager *m_connectionManager; - -private slots: - void devicesChanged(QLinkedList devices); - void connectionStatusChanged(); - void identificationModeChanged(); - void connectDisconnect(); -}; - -#endif // CONTROLLERPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui deleted file mode 100644 index a949d6a1d..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui +++ /dev/null @@ -1,163 +0,0 @@ - - - ControllerPage - - - - 0 - 0 - 600 - 400 - - - - WizardPage - - - - - 20 - 20 - 550 - 241 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot board identification</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">To continue we need to know what kind of OpenPilot board you want the wizard to create a configuration for. The wizard will try to automatically detect what type of board you have connected.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Please connect the board to a free usb port on your computer, or if a serial modem like BlueTooth, PipX or other is used, then power up the board and select the device to connect with from the list below. Then press Connect.</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">If the board already is connected and succesfully detected the board type will allready be displayed. You can disconnect and select another device if you need to detect another board.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">If your board isnt detected or if you want to create a configuration for a board that is not connected. Then select the Manual selection option below and select the board type from the drop down menu.</span></p></body></html> - - - Qt::AutoText - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - 20 - 270 - 560 - 110 - - - - - 8 - - - - OpenPilot board type - - - - false - - - - 150 - 70 - 260 - 22 - - - - - - - 150 - 30 - 260 - 22 - - - - - - - 434 - 70 - 111 - 23 - - - - Connect - - - - - - 441 - 33 - 101 - 17 - - - - Manual selection - - - - - - 20 - 32 - 121 - 16 - - - - - 75 - true - - - - Connection device: - - - - - - 20 - 72 - 131 - 16 - - - - - 75 - true - - - - Detected board type: - - - deviceCombo - connectButton - boardTypeCombo - manualCB - label_2 - label_3 - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp index dda55196e..3270e23ff 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp @@ -1,34 +1,8 @@ -/** - ****************************************************************************** - * - * @file endpage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup Setup Wizard Plugin - * @{ - * @brief A Wizard to make the initial setup easy for everyone. - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ #include "endpage.h" #include "ui_endpage.h" -EndPage::EndPage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), +EndPage::EndPage(QWidget *parent) : + QWizardPage(parent), ui(new Ui::EndPage) { setFinalPage(true); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h index afbeb6177..e4179e677 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h @@ -1,45 +1,18 @@ -/** - ****************************************************************************** - * - * @file endpage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - #ifndef ENDPAGE_H #define ENDPAGE_H -#include "abstractwizardpage.h" +#include namespace Ui { class EndPage; } -class EndPage : public AbstractWizardPage +class EndPage : public QWizardPage { Q_OBJECT public: - explicit EndPage(SetupWizard *wizard, QWidget *parent = 0); + explicit EndPage(QWidget *parent = 0); ~EndPage(); private: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui index f72b2d718..cc0a5c162 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui @@ -71,7 +71,7 @@ p, li { white-space: pre-wrap; } - Upload configuration + Uppload configuration diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp deleted file mode 100644 index 7295cc8a3..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ /dev/null @@ -1,42 +0,0 @@ -/** - ****************************************************************************** - * - * @file fixedwingpage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup FixedWingPage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "fixedwingpage.h" -#include "ui_fixedwingpage.h" - -FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), - ui(new Ui::FixedWingPage) -{ - ui->setupUi(this); - setFinalPage(true); -} - -FixedWingPage::~FixedWingPage() -{ - delete ui; -} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h deleted file mode 100644 index 697721a9e..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h +++ /dev/null @@ -1,49 +0,0 @@ -/** - ****************************************************************************** - * - * @file fixedwingpage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup FixedWingPage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef FIXEDWINGPAGE_H -#define FIXEDWINGPAGE_H - -#include "abstractwizardpage.h" - -namespace Ui { -class FixedWingPage; -} - -class FixedWingPage : public AbstractWizardPage -{ - Q_OBJECT - -public: - explicit FixedWingPage(SetupWizard *wizard, QWidget *parent = 0); - ~FixedWingPage(); - -private: - Ui::FixedWingPage *ui; -}; - -#endif // FIXEDWINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui deleted file mode 100644 index 0e4fde978..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui +++ /dev/null @@ -1,43 +0,0 @@ - - - FixedWingPage - - - - 0 - 0 - 600 - 400 - - - - WizardPage - - - - - 50 - 160 - 500 - 41 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">The fixed wing part the OpenPilot Setup Wizard is not yet implemented</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p></body></html> - - - Qt::AlignHCenter|Qt::AlignTop - - - true - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.cpp deleted file mode 100644 index 93bfc3503..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.cpp +++ /dev/null @@ -1,42 +0,0 @@ -/** - ****************************************************************************** - * - * @file helipage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup HeliPage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "helipage.h" -#include "ui_helipage.h" - -HeliPage::HeliPage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), - ui(new Ui::HeliPage) -{ - ui->setupUi(this); - setFinalPage(true); -} - -HeliPage::~HeliPage() -{ - delete ui; -} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.h deleted file mode 100644 index 2b2b5b894..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.h +++ /dev/null @@ -1,49 +0,0 @@ -/** - ****************************************************************************** - * - * @file helipage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup HeliPage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef HELIPAGE_H -#define HELIPAGE_H - -#include "abstractwizardpage.h" - -namespace Ui { -class HeliPage; -} - -class HeliPage : public AbstractWizardPage -{ - Q_OBJECT - -public: - explicit HeliPage(SetupWizard *wizard, QWidget *parent = 0); - ~HeliPage(); - -private: - Ui::HeliPage *ui; -}; - -#endif // HELIPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.ui deleted file mode 100644 index c3c6efd11..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.ui +++ /dev/null @@ -1,43 +0,0 @@ - - - HeliPage - - - - 0 - 0 - 600 - 400 - - - - WizardPage - - - - - 50 - 160 - 500 - 41 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">The helicopter part the OpenPilot Setup Wizard is not yet implemented</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p></body></html> - - - Qt::AlignHCenter|Qt::AlignTop - - - true - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp deleted file mode 100644 index 56ffa5fb0..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp +++ /dev/null @@ -1,125 +0,0 @@ -/** - ****************************************************************************** - * - * @file multipage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup MultiPage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "multipage.h" -#include "ui_multipage.h" -#include "setupwizard.h" - -MultiPage::MultiPage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), - ui(new Ui::MultiPage) -{ - ui->setupUi(this); - - QSvgRenderer *renderer = new QSvgRenderer(); - renderer->load(QString(":/configgadget/images/multirotor-shapes.svg")); - multiPic = new QGraphicsSvgItem(); - multiPic->setSharedRenderer(renderer); - QGraphicsScene *scene = new QGraphicsScene(this); - scene->addItem(multiPic); - ui->typeGraphicsView->setScene(scene); - - setupMultiTypesCombo(); - - // Default to Quad X since it is the most common setup - ui->typeCombo->setCurrentIndex(1); - connect(ui->typeCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateImageAndDescription())); -} - -MultiPage::~MultiPage() -{ - delete ui; -} - -void MultiPage::initializePage() -{ - updateImageAndDescription(); -} - -void MultiPage::setupMultiTypesCombo() -{ - ui->typeCombo->addItem("Tricopter", SetupWizard::MULTI_ROTOR_TRI_Y); - ui->typeCombo->addItem("Quadcopter X", SetupWizard::MULTI_ROTOR_QUAD_X); - ui->typeCombo->addItem("Quadcopter +", SetupWizard::MULTI_ROTOR_QUAD_PLUS); - ui->typeCombo->addItem("Hexacopter", SetupWizard::MULTI_ROTOR_HEXA); - ui->typeCombo->addItem("Hexacopter Coax", SetupWizard::MULTI_ROTOR_HEXA_COAX_Y); - ui->typeCombo->addItem("Hexacopter H", SetupWizard::MULTI_ROTOR_HEXA_H); - ui->typeCombo->addItem("Octocopter", SetupWizard::MULTI_ROTOR_OCTO); - ui->typeCombo->addItem("Octocopter Coax X", SetupWizard::MULTI_ROTOR_OCTO_COAX_X); - ui->typeCombo->addItem("Octocopter Coax +", SetupWizard::MULTI_ROTOR_OCTO_COAX_PLUS); - ui->typeCombo->addItem("Octocopter V", SetupWizard::MULTI_ROTOR_OCTO_V); -} - -void MultiPage::updateImageAndDescription() -{ - SetupWizard::MULTI_ROTOR_SUB_TYPE type = (SetupWizard::MULTI_ROTOR_SUB_TYPE) ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); - QString elementId = ""; - QString description = "Descriptive text with information about "; - description.append(ui->typeCombo->currentText()); - description.append(" multirotors."); - switch(type) - { - case SetupWizard::MULTI_ROTOR_TRI_Y: - elementId = "tri"; - break; - case SetupWizard::MULTI_ROTOR_QUAD_X: - elementId = "quad-x"; - break; - case SetupWizard::MULTI_ROTOR_QUAD_PLUS: - elementId = "quad-plus"; - break; - case SetupWizard::MULTI_ROTOR_HEXA: - elementId = "quad-hexa"; - break; - case SetupWizard::MULTI_ROTOR_HEXA_COAX_Y: - elementId = "hexa-coax"; - break; - case SetupWizard::MULTI_ROTOR_HEXA_H: - elementId = "quad-hexa-H"; - break; - case SetupWizard::MULTI_ROTOR_OCTO: - elementId = "quad-octo"; - break; - case SetupWizard::MULTI_ROTOR_OCTO_COAX_X: - elementId = "octo-coax-X"; - break; - case SetupWizard::MULTI_ROTOR_OCTO_COAX_PLUS: - elementId = "octo-coax-P"; - break; - case SetupWizard::MULTI_ROTOR_OCTO_V: - elementId = "quad-octo-v"; - break; - default: - elementId = ""; - break; - } - multiPic->setElementId(elementId); - ui->typeGraphicsView->setSceneRect(multiPic->boundingRect()); - ui->typeGraphicsView->fitInView(multiPic, Qt::KeepAspectRatio); - - ui->typeDescription->setText(description); -} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h deleted file mode 100644 index bc9f822ad..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h +++ /dev/null @@ -1,59 +0,0 @@ -/** - ****************************************************************************** - * - * @file multipage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup MultiPage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef MULTIPAGE_H -#define MULTIPAGE_H - -#include -#include - -#include "abstractwizardpage.h" - -namespace Ui { -class MultiPage; -} - -class MultiPage : public AbstractWizardPage -{ - Q_OBJECT - -public: - explicit MultiPage(SetupWizard *wizard, QWidget *parent = 0); - ~MultiPage(); - - void initializePage(); - -private: - Ui::MultiPage *ui; - void setupMultiTypesCombo(); - QGraphicsSvgItem *multiPic; - -private slots: - void updateImageAndDescription(); -}; - -#endif // MULTIPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui deleted file mode 100644 index 2c33fb4d5..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui +++ /dev/null @@ -1,146 +0,0 @@ - - - MultiPage - - - - 0 - 0 - 600 - 400 - - - - WizardPage - - - - - 20 - 20 - 541 - 151 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot multirotor configuration</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This part of the wizard will set up the OpenPilot controller for use with a flying platform with multiple rotors. The wizard supports the most common types of multirotors. Other variants of multirotors can be configured by using custom configuration options in the configuration plugin in GCS.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Please select the type of multirotor you want to create a configuration for below:</span></p></body></html> - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - 20 - 180 - 561 - 200 - - - - - 10 - - - - Multirotor type selection - - - - - 20 - 32 - 121 - 16 - - - - - 75 - true - - - - Multirotor type: - - - - - - 150 - 30 - 220 - 22 - - - - - - - 390 - 30 - 150 - 150 - - - - - 0 - 0 - - - - QFrame::NoFrame - - - 0 - - - 0 - - - Qt::ScrollBarAlwaysOff - - - Qt::ScrollBarAlwaysOff - - - false - - - - - - 20 - 69 - 351 - 111 - - - - Qt::ScrollBarAlwaysOn - - - Qt::ScrollBarAlwaysOff - - - Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse - - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.cpp deleted file mode 100644 index 57a43fda8..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.cpp +++ /dev/null @@ -1,42 +0,0 @@ -/** - ****************************************************************************** - * - * @file notyetimplementedpage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup NotYetImplementedPage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "notyetimplementedpage.h" -#include "ui_notyetimplementedpage.h" - -NotYetImplementedPage::NotYetImplementedPage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), - ui(new Ui::NotYetImplementedPage) -{ - ui->setupUi(this); - setFinalPage(true); -} - -NotYetImplementedPage::~NotYetImplementedPage() -{ - delete ui; -} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.h deleted file mode 100644 index 4f323d9fc..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.h +++ /dev/null @@ -1,49 +0,0 @@ -/** - ****************************************************************************** - * - * @file notyetimplementedpage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup NotYetImplementedPage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef NOTYETIMPLEMENTEDPAGE_H -#define NOTYETIMPLEMENTEDPAGE_H - -#include "abstractwizardpage.h" - -namespace Ui { -class NotYetImplementedPage; -} - -class NotYetImplementedPage : public AbstractWizardPage -{ - Q_OBJECT - -public: - explicit NotYetImplementedPage(SetupWizard *wizard, QWidget *parent = 0); - ~NotYetImplementedPage(); - -private: - Ui::NotYetImplementedPage *ui; -}; - -#endif // NOTYETIMPLEMENTEDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.ui deleted file mode 100644 index b5b54240d..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.ui +++ /dev/null @@ -1,43 +0,0 @@ - - - NotYetImplementedPage - - - - 0 - 0 - 600 - 400 - - - - WizardPage - - - - - 50 - 190 - 501 - 31 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">This part the OpenPilot Setup Wizard is not yet implemented</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p></body></html> - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp index 46110a9e4..f36631bb0 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp @@ -1,34 +1,8 @@ -/** - ****************************************************************************** - * - * @file startpage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup Setup Wizard Plugin - * @{ - * @brief A Wizard to make the initial setup easy for everyone. - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ #include "startpage.h" #include "ui_startpage.h" -StartPage::StartPage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), +StartPage::StartPage(QWidget *parent) : + QWizardPage(parent), ui(new Ui::StartPage) { ui->setupUi(this); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h index 3e9e120cc..f6cf9b6cd 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h @@ -1,44 +1,18 @@ -/** - ****************************************************************************** - * - * @file startpage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup Setup Wizard Plugin - * @{ - * @brief A Wizard to make the initial setup easy for everyone. - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ #ifndef STARTPAGE_H #define STARTPAGE_H -#include "abstractwizardpage.h" +#include namespace Ui { class StartPage; } -class StartPage : public AbstractWizardPage +class StartPage : public QWizardPage { Q_OBJECT public: - explicit StartPage(SetupWizard *wizard, QWidget *parent = 0); + explicit StartPage(QWidget *parent = 0); ~StartPage(); private: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.cpp deleted file mode 100644 index a28724f2f..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.cpp +++ /dev/null @@ -1,42 +0,0 @@ -/** - ****************************************************************************** - * - * @file surfacepage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup SurfacePage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "surfacepage.h" -#include "ui_surfacepage.h" - -SurfacePage::SurfacePage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), - ui(new Ui::SurfacePage) -{ - ui->setupUi(this); - setFinalPage(true); -} - -SurfacePage::~SurfacePage() -{ - delete ui; -} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.h deleted file mode 100644 index 593aa1fca..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.h +++ /dev/null @@ -1,49 +0,0 @@ -/** - ****************************************************************************** - * - * @file surfacepage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup SurfacePage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef SURFACEPAGE_H -#define SURFACEPAGE_H - -#include "abstractwizardpage.h" - -namespace Ui { -class SurfacePage; -} - -class SurfacePage : public AbstractWizardPage -{ - Q_OBJECT - -public: - explicit SurfacePage(SetupWizard *wizard, QWidget *parent = 0); - ~SurfacePage(); - -private: - Ui::SurfacePage *ui; -}; - -#endif // SURFACEPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.ui deleted file mode 100644 index 988bc300a..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.ui +++ /dev/null @@ -1,43 +0,0 @@ - - - SurfacePage - - - - 0 - 0 - 600 - 400 - - - - WizardPage - - - - - 50 - 160 - 500 - 41 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">The surface vehicle part the OpenPilot Setup Wizard is not yet implemented</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p></body></html> - - - Qt::AlignHCenter|Qt::AlignTop - - - true - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp deleted file mode 100644 index a616a1194..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp +++ /dev/null @@ -1,61 +0,0 @@ -/** - ****************************************************************************** - * - * @file vehiclepage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup VehiclePage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "vehiclepage.h" -#include "ui_vehiclepage.h" - -VehiclePage::VehiclePage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), - ui(new Ui::VehiclePage) -{ - ui->setupUi(this); -} - -VehiclePage::~VehiclePage() -{ - delete ui; -} - -bool VehiclePage::validatePage() -{ - if(ui->multirotorButton->isChecked()) { - getWizard()->setVehicleType(SetupWizard::VEHICLE_MULTI); - } - else if(ui->fixedwingButton->isChecked()) { - getWizard()->setVehicleType(SetupWizard::VEHICLE_FIXEDWING); - } - else if(ui->heliButton->isChecked()) { - getWizard()->setVehicleType(SetupWizard::VEHICLE_HELI); - } - else if(ui->surfaceButton->isChecked()) { - getWizard()->setVehicleType(SetupWizard::VEHICLE_SURFACE); - } - else { - getWizard()->setVehicleType(SetupWizard::VEHICLE_UNKNOWN); - } - return true; -} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h deleted file mode 100644 index 5e72a3d21..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h +++ /dev/null @@ -1,50 +0,0 @@ -/** - ****************************************************************************** - * - * @file vehiclepage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @addtogroup - * @{ - * @addtogroup VehiclePage - * @{ - * @brief - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef VEHICLEPAGE_H -#define VEHICLEPAGE_H - -#include "abstractwizardpage.h" - -namespace Ui { -class VehiclePage; -} - -class VehiclePage : public AbstractWizardPage -{ - Q_OBJECT - -public: - explicit VehiclePage(SetupWizard *wizard, QWidget *parent = 0); - ~VehiclePage(); - bool validatePage(); - -private: - Ui::VehiclePage *ui; -}; - -#endif // VEHICLEPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui deleted file mode 100644 index fdc2d47d2..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui +++ /dev/null @@ -1,168 +0,0 @@ - - - VehiclePage - - - - 0 - 0 - 600 - 400 - - - - WizardPage - - - - - 20 - 20 - 550 - 131 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Vehicle type selection</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">To continue the wizard needs to know what type of vehicle that the OpenPilot controller board is going to be used with. This step is cruicial since most of the following configuration is unique per vehicle type.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">So go ahead and select the type of vehicle you want to create a configuration for.</span></p></body></html> - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - 20 - 200 - 561 - 181 - - - - - 0 - 0 - - - - Supported vehicle types - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - 50 - 40 - 100 - 100 - - - - Tricopter, Quadcopter, Hexacopter, Octocopter - - - Multirotor - - - true - - - true - - - true - - - false - - - - - - 170 - 40 - 100 - 100 - - - - Airplane, Sloper, Jet - - - Fixed wing - - - true - - - true - - - false - - - - - - 290 - 40 - 100 - 100 - - - - Helicopter - - - true - - - true - - - false - - - - - - 410 - 40 - 100 - 100 - - - - Car, Boat, U-Boat - - - Surface - - - true - - - true - - - false - - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index f11762bf6..26a5e386a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file setupwizard.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup Setup Wizard Plugin @@ -28,72 +28,27 @@ #include "setupwizard.h" #include "pages/startpage.h" #include "pages/endpage.h" -#include "pages/controllerpage.h" -#include "pages/vehiclepage.h" -#include "pages/multipage.h" -#include "pages/fixedwingpage.h" -#include "pages/helipage.h" -#include "pages/surfacepage.h" -#include "pages/notyetimplementedpage.h" SetupWizard::SetupWizard(QWidget *parent) : QWizard(parent) { setWindowTitle("OpenPilot Setup Wizard"); - m_controllerType = CONTROLLER_UNKNOWN; - m_vehicleType = VEHICLE_UNKNOWN; createPages(); } int SetupWizard::nextId() const { switch (currentId()) { - case PAGE_START: - return PAGE_CONTROLLER; - case PAGE_CONTROLLER: { - switch(getControllerType()) - { - case CONTROLLER_CC: - case CONTROLLER_CC3D: - return PAGE_VEHICLES; - default: - return PAGE_NOTYETIMPLEMENTED; - } - } - case PAGE_VEHICLES: { - switch(getVehicleType()) - { - case VEHICLE_FIXEDWING: - return PAGE_FIXEDWING; - case VEHICLE_HELI: - return PAGE_HELI; - case VEHICLE_SURFACE: - return PAGE_SURFACE; - case VEHICLE_MULTI: - return PAGE_MULTI; - default: - return PAGE_NOTYETIMPLEMENTED; - } - } - case PAGE_MULTI: - return PAGE_END; - case PAGE_NOTYETIMPLEMENTED: - return PAGE_END; - default: - return -1; + case PAGE_START: + return PAGE_END; + default: + return -1; } } void SetupWizard::createPages() { - setPage(PAGE_START, new StartPage(this)); - setPage(PAGE_CONTROLLER, new ControllerPage(this)); - setPage(PAGE_VEHICLES, new VehiclePage(this)); - setPage(PAGE_MULTI, new MultiPage(this)); - setPage(PAGE_FIXEDWING, new FixedWingPage(this)); - setPage(PAGE_HELI, new HeliPage(this)); - setPage(PAGE_SURFACE, new SurfacePage(this)); - setPage(PAGE_NOTYETIMPLEMENTED, new NotYetImplementedPage(this)); - setPage(PAGE_END, new EndPage(this)); + setPage(PAGE_START, new StartPage()); + setPage(PAGE_END, new EndPage()); setStartId(PAGE_START); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h index 34b20dd81..42f75556a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file setupwizard.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup Setup Wizard Plugin @@ -37,25 +37,9 @@ class SetupWizard : public QWizard public: SetupWizard(QWidget *parent = 0); int nextId() const; - enum CONTROLLER_TYPE {CONTROLLER_UNKNOWN, CONTROLLER_CC, CONTROLLER_CC3D, CONTROLLER_REVO, CONTROLLER_PIPX}; - enum VEHICLE_TYPE {VEHICLE_UNKNOWN, VEHICLE_MULTI, VEHICLE_FIXEDWING, VEHICLE_HELI, VEHICLE_SURFACE}; - enum MULTI_ROTOR_SUB_TYPE {MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS, - MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, - MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS}; - - void setControllerType(SetupWizard::CONTROLLER_TYPE type) { m_controllerType = type; } - SetupWizard::CONTROLLER_TYPE getControllerType() const { return m_controllerType; } - - void setVehicleType(SetupWizard::VEHICLE_TYPE type) { m_vehicleType = type; } - SetupWizard::VEHICLE_TYPE getVehicleType() const { return m_vehicleType; } - private: - enum {PAGE_START, PAGE_CONTROLLER, PAGE_VEHICLES, PAGE_MULTI, PAGE_FIXEDWING, - PAGE_HELI, PAGE_SURFACE, PAGE_NOTYETIMPLEMENTED, PAGE_END}; + enum {PAGE_START, PAGE_END}; void createPages(); - - CONTROLLER_TYPE m_controllerType; - VEHICLE_TYPE m_vehicleType; }; #endif // SETUPWIZARD_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index 98ece1c83..20d13155d 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -1,49 +1,21 @@ TEMPLATE = lib TARGET = SetupWizard -QT += svg - + include(../../openpilotgcsplugin.pri) include(../../plugins/coreplugin/coreplugin.pri) -include(../../plugins/uavobjectutil/uavobjectutil.pri) HEADERS += setupwizardplugin.h \ setupwizard.h \ pages/startpage.h \ - pages/endpage.h \ - pages/controllerpage.h \ - pages/vehiclepage.h \ - pages/notyetimplementedpage.h \ - pages/multipage.h \ - pages/fixedwingpage.h \ - pages/helipage.h \ - pages/surfacepage.h \ - pages/abstractwizardpage.h + pages/endpage.h SOURCES += setupwizardplugin.cpp \ setupwizard.cpp \ pages/startpage.cpp \ - pages/endpage.cpp \ - pages/controllerpage.cpp \ - pages/vehiclepage.cpp \ - pages/notyetimplementedpage.cpp \ - pages/multipage.cpp \ - pages/fixedwingpage.cpp \ - pages/helipage.cpp \ - pages/surfacepage.cpp \ - pages/abstractwizardpage.cpp + pages/endpage.cpp OTHER_FILES += SetupWizard.pluginspec FORMS += \ pages/startpage.ui \ - pages/endpage.ui \ - pages/controllerpage.ui \ - pages/vehiclepage.ui \ - pages/notyetimplementedpage.ui \ - pages/multipage.ui \ - pages/fixedwingpage.ui \ - pages/helipage.ui \ - pages/surfacepage.ui - -RESOURCES += \ - wizardResources.qrc + pages/endpage.ui \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp index 9f5b5c67b..a6dddbd4c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp @@ -1,8 +1,8 @@ /** ****************************************************************************** * - * @file setupwizardplugin.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @file donothingplugin.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup SetupWizardPlugin diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h index 96ca9e038..4caecbcd0 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h @@ -1,8 +1,8 @@ /** ****************************************************************************** * - * @file setupwizardplugin.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @file donothingplugin.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup SetupWizardPlugin diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc deleted file mode 100644 index 1358ce976..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ /dev/null @@ -1,3 +0,0 @@ - - - From 82dc7e595756b27539435b86ce6d35731a8f1058 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Tue, 24 Jul 2012 22:32:08 +0100 Subject: [PATCH 064/543] Revert "OP-39 Initial commit. Created new sub project to plugins project." This reverts commit 532fc3071a9fb850bdb97f0b030937f835f38d34. Conflicts: ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h --- ground/openpilotgcs/src/plugins/plugins.pro | 7 -- .../setupwizard/SetupWizard.pluginspec | 10 --- .../src/plugins/setupwizard/setupwizard.cpp | 54 ------------ .../src/plugins/setupwizard/setupwizard.h | 45 ---------- .../src/plugins/setupwizard/setupwizard.pro | 21 ----- .../plugins/setupwizard/setupwizardplugin.cpp | 85 ------------------- .../plugins/setupwizard/setupwizardplugin.h | 50 ----------- 7 files changed, 272 deletions(-) delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/SetupWizard.pluginspec delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h diff --git a/ground/openpilotgcs/src/plugins/plugins.pro b/ground/openpilotgcs/src/plugins/plugins.pro index c2c7c922b..154335e3a 100644 --- a/ground/openpilotgcs/src/plugins/plugins.pro +++ b/ground/openpilotgcs/src/plugins/plugins.pro @@ -210,13 +210,6 @@ plugin_uavobjectwidgetutils.depends += plugin_uavobjects plugin_uavobjectwidgetutils.depends += plugin_uavsettingsimportexport SUBDIRS += plugin_uavobjectwidgetutils -# Setup Wizard plugin -plugin_setupwizard.subdir = setupwizard -plugin_setupwizard.depends = plugin_coreplugin -plugin_setupwizard.depends += plugin_uavobjects -plugin_setupwizard.depends += plugin_uavsettingsimportexport -SUBDIRS += plugin_setupwizard - # Junsi Powerlog plugin #plugin_powerlog.subdir = powerlog #plugin_powerlog.depends = plugin_coreplugin diff --git a/ground/openpilotgcs/src/plugins/setupwizard/SetupWizard.pluginspec b/ground/openpilotgcs/src/plugins/setupwizard/SetupWizard.pluginspec deleted file mode 100644 index 4425b290e..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/SetupWizard.pluginspec +++ /dev/null @@ -1,10 +0,0 @@ - - The OpenPilot Project - (C) 2012 OpenPilot Project - The GNU Public License (GPL) Version 3 - A plugin that provides a setup wizard for easy initial setup of airframes. - http://www.openpilot.org - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp deleted file mode 100644 index 26a5e386a..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ /dev/null @@ -1,54 +0,0 @@ -/** - ****************************************************************************** - * - * @file setupwizard.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup Setup Wizard Plugin - * @{ - * @brief A Wizard to make the initial setup easy for everyone. - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "setupwizard.h" -#include "pages/startpage.h" -#include "pages/endpage.h" - -SetupWizard::SetupWizard(QWidget *parent) : QWizard(parent) -{ - setWindowTitle("OpenPilot Setup Wizard"); - createPages(); -} - -int SetupWizard::nextId() const -{ - switch (currentId()) { - case PAGE_START: - return PAGE_END; - default: - return -1; - } -} - -void SetupWizard::createPages() -{ - setPage(PAGE_START, new StartPage()); - setPage(PAGE_END, new EndPage()); - - setStartId(PAGE_START); -} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h deleted file mode 100644 index 42f75556a..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ /dev/null @@ -1,45 +0,0 @@ -/** - ****************************************************************************** - * - * @file setupwizard.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup Setup Wizard Plugin - * @{ - * @brief A Wizards to make the initial setup easy for everyone. - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef SETUPWIZARD_H -#define SETUPWIZARD_H - -#include - -class SetupWizard : public QWizard -{ - Q_OBJECT - -public: - SetupWizard(QWidget *parent = 0); - int nextId() const; -private: - enum {PAGE_START, PAGE_END}; - void createPages(); -}; - -#endif // SETUPWIZARD_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro deleted file mode 100644 index 20d13155d..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ /dev/null @@ -1,21 +0,0 @@ - -TEMPLATE = lib -TARGET = SetupWizard - -include(../../openpilotgcsplugin.pri) -include(../../plugins/coreplugin/coreplugin.pri) - -HEADERS += setupwizardplugin.h \ - setupwizard.h \ - pages/startpage.h \ - pages/endpage.h -SOURCES += setupwizardplugin.cpp \ - setupwizard.cpp \ - pages/startpage.cpp \ - pages/endpage.cpp - -OTHER_FILES += SetupWizard.pluginspec - -FORMS += \ - pages/startpage.ui \ - pages/endpage.ui \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp deleted file mode 100644 index a6dddbd4c..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp +++ /dev/null @@ -1,85 +0,0 @@ -/** - ****************************************************************************** - * - * @file donothingplugin.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup SetupWizardPlugin - * @{ - * @brief A Setup Wizard Plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#include "setupwizardplugin.h" - -#include -#include -#include -#include - -#include -#include -#include -#include - -SetupWizardPlugin::SetupWizardPlugin() -{ - // Do nothing -} - -SetupWizardPlugin::~SetupWizardPlugin() -{ -} - -bool SetupWizardPlugin::initialize(const QStringList& args, QString *errMsg) -{ - Q_UNUSED(args); - Q_UNUSED(errMsg); - - // Add Menu entry - Core::ActionManager* am = Core::ICore::instance()->actionManager(); - Core::ActionContainer* ac = am->actionContainer(Core::Constants::M_TOOLS); - - Core::Command* cmd = am->registerAction(new QAction(this), - "SetupWizardPlugin.ShowSetupWizard", - QList() << - Core::Constants::C_GLOBAL_ID); - cmd->setDefaultKeySequence(QKeySequence("Ctrl+W")); - cmd->action()->setText(tr("OpenPilot Setup Wizard")); - - ac->menu()->addSeparator(); - ac->appendGroup("Wizard"); - ac->addAction(cmd, "Wizard"); - - connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(showSetupWizard())); - return true; -} - -void SetupWizardPlugin::extensionsInitialized() -{ -} - -void SetupWizardPlugin::shutdown() -{ -} - -void SetupWizardPlugin::showSetupWizard() -{ - SetupWizard().exec(); -} - -Q_EXPORT_PLUGIN(SetupWizardPlugin) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h deleted file mode 100644 index 4caecbcd0..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h +++ /dev/null @@ -1,50 +0,0 @@ -/** - ****************************************************************************** - * - * @file donothingplugin.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup SetupWizardPlugin - * @{ - * @brief A Setup Wizard Plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef SETUPWIZARDPLUGIN_H -#define SETUPWIZARDPLUGIN_H - -#include -#include -#include "setupwizard.h" - -class SetupWizardPlugin : public ExtensionSystem::IPlugin -{ - Q_OBJECT -public: - SetupWizardPlugin(); - ~SetupWizardPlugin(); - - void extensionsInitialized(); - bool initialize(const QStringList & arguments, QString * errorString); - void shutdown(); - -private slots: - void showSetupWizard(); - -}; - -#endif // SETUPWIZARDPLUGIN_H From 8c4806fa14ae22ebbda31385ff651a61f50c8df8 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Tue, 24 Jul 2012 22:32:54 +0100 Subject: [PATCH 065/543] Revert "OP-39 Start and End pages added. Placeholder text added." This reverts commit 559be15142c5d6ef425b855aeee673a181ad023f. Conflicts: ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h --- .../src/plugins/setupwizard/pages/endpage.cpp | 15 ---- .../src/plugins/setupwizard/pages/endpage.h | 22 ----- .../src/plugins/setupwizard/pages/endpage.ui | 80 ------------------- .../plugins/setupwizard/pages/startpage.cpp | 14 ---- .../src/plugins/setupwizard/pages/startpage.h | 22 ----- .../plugins/setupwizard/pages/startpage.ui | 56 ------------- 6 files changed, 209 deletions(-) delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp deleted file mode 100644 index 3270e23ff..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp +++ /dev/null @@ -1,15 +0,0 @@ -#include "endpage.h" -#include "ui_endpage.h" - -EndPage::EndPage(QWidget *parent) : - QWizardPage(parent), - ui(new Ui::EndPage) -{ - setFinalPage(true); - ui->setupUi(this); -} - -EndPage::~EndPage() -{ - delete ui; -} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h deleted file mode 100644 index e4179e677..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h +++ /dev/null @@ -1,22 +0,0 @@ -#ifndef ENDPAGE_H -#define ENDPAGE_H - -#include - -namespace Ui { -class EndPage; -} - -class EndPage : public QWizardPage -{ - Q_OBJECT - -public: - explicit EndPage(QWidget *parent = 0); - ~EndPage(); - -private: - Ui::EndPage *ui; -}; - -#endif // ENDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui deleted file mode 100644 index cc0a5c162..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui +++ /dev/null @@ -1,80 +0,0 @@ - - - EndPage - - - - 0 - 0 - 600 - 400 - - - - - 600 - 400 - - - - WizardPage - - - - - 20 - 20 - 550 - 141 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Setup complete</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">The wizard have now gathered enough information to create a baseline configuration for your OpenPilot controller board to use with your vehicle.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">You now have two choices:</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">- Upload configuration directly to the currently connected OpenPilot controller board.</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">- Save the configuration to a file for later uploading using the configuration import plugin in GCS.</span></p></body></html> - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - 420 - 290 - 125 - 23 - - - - Save configuration... - - - - - - 420 - 340 - 125 - 23 - - - - Uppload configuration - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp deleted file mode 100644 index f36631bb0..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp +++ /dev/null @@ -1,14 +0,0 @@ -#include "startpage.h" -#include "ui_startpage.h" - -StartPage::StartPage(QWidget *parent) : - QWizardPage(parent), - ui(new Ui::StartPage) -{ - ui->setupUi(this); -} - -StartPage::~StartPage() -{ - delete ui; -} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h deleted file mode 100644 index f6cf9b6cd..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h +++ /dev/null @@ -1,22 +0,0 @@ -#ifndef STARTPAGE_H -#define STARTPAGE_H - -#include - -namespace Ui { -class StartPage; -} - -class StartPage : public QWizardPage -{ - Q_OBJECT - -public: - explicit StartPage(QWidget *parent = 0); - ~StartPage(); - -private: - Ui::StartPage *ui; -}; - -#endif // STARTPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui deleted file mode 100644 index 0f656f35c..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui +++ /dev/null @@ -1,56 +0,0 @@ - - - StartPage - - - - 0 - 0 - 640 - 400 - - - - - 640 - 400 - - - - WizardPage - - - - - 20 - 20 - 550 - 350 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Welcome to the OpenPilot Setup Wizard</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This wizard will guide you through the basic steps of setting up your OpenPilot controller board. The following pages contains simple questions about your vehicle and its characteristics. </span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">From the information </span><span style=" font-size:10pt;">gathered</span><span style=" font-size:10pt;"> the wizard will create a baseline configuration that should be good enough for you to get a quick start using your OpenPilot product.</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">The baseline configuration can, if desired, be uploaded to the OpenPilot Controller board at the end of this wizard.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This wizard does not contain the full range of settings available in the GCS Config plugin. All configuration parameters can be changed at later by using the GCS Config plugin.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Ok, lets start the configuration by clicking on the 'Next' button below.</span></p></body></html> - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - From 48b3cf71011427fd1e05d82dfcd06fcb0fd76d86 Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Tue, 24 Jul 2012 23:46:21 -0700 Subject: [PATCH 066/543] fixed the airframe form so it scrolls AND has the shiny new popups --- .../src/plugins/config/airframe.ui | 5462 +++++++++-------- 1 file changed, 2889 insertions(+), 2573 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 16b0172a3..a9de06541 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -6,14 +6,14 @@ 0 0 - 939 - 657 + 833 + 852 Form - + @@ -23,551 +23,193 @@ Mixer Settings - + - 5 + 12 - - - - - - 75 - true - - - - Vehicle type: - - - - - - - Select aircraft type here - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Horizontal + + + + 0 + 0 + - - - - - - 0 + + + 0 + 0 + - - - true + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + + + QFrame::NoFrame + + + QFrame::Plain + + + true + + + + + 0 + 0 + 779 + 691 + - - false - - - - + + + + + QLayout::SetFixedSize + - - - - - - 0 - 0 - - - - - 75 - true - - - - Airplane type: - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - + + + + 0 + 0 + + + + + 75 + true + + + + Vehicle type: + + - + + + Select aircraft type here + + - - - - - - 0 - 0 - - - - - 230 - 100 - - - - Output Channel Assignments - - - - - - Engine - - - - - - - Select output channel for the engine - - - - - - - - 60 - 0 - - - - Aileron 1 - - - - - - - Select output channel for the first aileron (or elevon) - - - - - - - false - - - - 60 - 0 - - - - Aileron 2 - - - - - - - false - - - Select output channel for the second aileron (or elevon) - - - - - - - - 67 - 0 - - - - Elevator 1 - - - - - - - Select output channel for the first elevator - - - - - - - false - - - - 67 - 0 - - - - Elevator 2 - - - - - - - false - - - Select output channel for a secondary elevator - - - - - - - Rudder 1 - - - - - - - Select output channel for the first rudder - - - - - - - Rudder 2 - - - - - - - Select output channel for a secondary rudder - - - - - - - Qt::Vertical - - - - 20 - 20 - - - - - - - - - - - - 0 - 0 - - - - Elevon Mix - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 0 - 20 - - - - - - - - - - - - - 65 - 0 - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Rudder % - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - 100 - - - 50 - - - Qt::Vertical - - - - - - - 50 - - - Qt::AlignCenter - - - - - - - - - - - - 50 - 0 - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Pitch % - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - 100 - - - 50 - - - Qt::Vertical - - - - - - - 50 - - - Qt::AlignCenter - - - - - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 100 - - - - Throttle Curve - - - - - - - 1 - 1 - - - - - 0 - 0 - - - - - 500 - 500 - - - - - 10 - 10 - - - - - 300 - 350 - - - - - - - - - - - + - Qt::Vertical + Qt::Horizontal + + + QSizePolicy::Expanding - 20 - 40 + 2 + 20 - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 75 - true - - - - Mixer OK - - - - - - - - - - - - - + + + + + 0 + 0 + + + + + 775 + 16777215 + + + + 1 + + + + true + + + false + + - + - + - + + + + 0 + 0 + + 75 @@ -575,19 +217,15 @@ margin:1px; - Frame type: + Airplane type: - - - Select the Multirotor frame type here. - - + - + Qt::Horizontal @@ -602,13 +240,448 @@ margin:1px; - + + + + - + + + + 0 + 0 + + + + + 230 + 100 + + + + Output Channel Assignments + + + + + + Engine + + + + + + + Select output channel for the engine + + + + + + + + 60 + 0 + + + + Aileron 1 + + + + + + + Select output channel for the first aileron (or elevon) + + + + + + + false + + + + 60 + 0 + + + + Aileron 2 + + + + + + + false + + + Select output channel for the second aileron (or elevon) + + + + + + + + 67 + 0 + + + + Elevator 1 + + + + + + + Select output channel for the first elevator + + + + + + + false + + + + 67 + 0 + + + + Elevator 2 + + + + + + + false + + + Select output channel for a secondary elevator + + + + + + + Rudder 1 + + + + + + + Select output channel for the first rudder + + + + + + + Rudder 2 + + + + + + + Select output channel for a secondary rudder + + + + + + + Qt::Vertical + + + + 20 + 20 + + + + + + + + + + + + 0 + 0 + + + + Elevon Mix + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 0 + 20 + + + + + + + + + + + + + 65 + 0 + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Rudder % + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + 50 + + + Qt::AlignCenter + + + + + + + + + + + + 50 + 0 + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Pitch % + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + 50 + + + Qt::AlignCenter + + + + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 100 + + + + Throttle Curve + + + + + + + 1 + 1 + + + + + 0 + 0 + + + + + 500 + 500 + + + + + 10 + 10 + + + + + 300 + 350 + + + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 75 + true + + + + Mixer OK + + + + + + + + + + + + + + + + + - + - + 75 @@ -616,12 +689,19 @@ margin:1px; - Mix Level + Frame type: - + + + Select the Multirotor frame type here. + + + + + Qt::Horizontal @@ -636,279 +716,703 @@ margin:1px; - + - + - - - - 30 - 0 - - - - 100 - - - Qt::AlignCenter - - + + + + + + 75 + true + + + + Mix Level + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + - - - - 35 - 0 - - - - Weight of Roll mixing in percent. + + + + + + + + 30 + 0 + + + + 100 + + + Qt::AlignCenter + + + + + + + + 35 + 0 + + + + Weight of Roll mixing in percent. Typical values are 100% for + configuration and 50% for X configuration on quads. - - - 100 - - - 100 - - - Qt::Vertical - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + 100 + + + 100 + + + Qt::Vertical + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - R - - - Qt::AlignCenter - - - - - - - - - - - - 0 - 0 - - - - 100 - - - Qt::AlignCenter - - - - - - - - 35 - 0 - - - - Weight of Pitch mixing in percent. + + + R + + + Qt::AlignCenter + + + + + + + + + + + + 0 + 0 + + + + 100 + + + Qt::AlignCenter + + + + + + + + 35 + 0 + + + + Weight of Pitch mixing in percent. Typical values are 100% for + configuration and 50% for X configuration on quads. - - - 100 - - - 100 - - - Qt::Vertical - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + 100 + + + 100 + + + Qt::Vertical + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - P - - - Qt::AlignCenter - - - - - - - - - - - - 0 - 0 - - - - 50 - - - Qt::AlignCenter - - - - - - - - 40 - 0 - - - - Weight of Yaw mixing in percent. + + + P + + + Qt::AlignCenter + + + + + + + + + + + + 0 + 0 + + + + 50 + + + Qt::AlignCenter + + + + + + + + 40 + 0 + + + + Weight of Yaw mixing in percent. Typical value is 50% for + or X configuration on quads. - - - -100 - - - 100 - - - 50 - - - Qt::Vertical - - - - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + -100 + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; font: bold 12px; margin:1px; - - - Y - - - Qt::AlignCenter - - + + + Y + + + Qt::AlignCenter + + + + + + + + + + + 0 + 0 + + + + + 80 + 80 + + + + background:transparent + + + QFrame::NoFrame + + + QFrame::Plain + + + - + - + 0 0 - 110 - 110 + 300 + 300 - - background:transparent - - - QFrame::NoFrame - - - QFrame::Plain + + Throttle Curve + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 10 + 10 + + + + + 300 + 350 + + + + background:transparent + + + + + - - - - - - Throttle Curve - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 10 - 10 - - - - - 300 - 350 - - - - background:transparent - - - - - - - - - - - - 10 - - - - + + + 10 + - + + + + + + + + 75 + true + + + + Tricopter Yaw + + + + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 40 + 20 + + + + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + channel: + + + + + + + false + + + + 0 + 0 + + + + + 40 + 0 + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + Qt::Horizontal + + + + 10 + 20 + + + + + + + + Motor output channels + + + + 1 + + + 1 + + + + + QLayout::SetMaximumSize + + + QFormLayout::AllNonFixedFieldsGrow + + + 3 + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 1 + + + + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 2 + + + + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 3 + + + + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 4 + + + + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 0 + 20 + + + + + + + + + + QLayout::SetMaximumSize + + + QFormLayout::AllNonFixedFieldsGrow + + + 3 + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 5 + + + + + + + false + + + + 0 + 0 + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 6 + + + + + + + false + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 7 + + + + + + + false + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + 8 + + + + + + + false + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 20 + + + + + + + + + + + + + + + + + Qt::Horizontal + + + QSizePolicy::Expanding + + + + 40 + 20 + + + + + + + + + 0 + 0 + + 75 @@ -916,12 +1420,72 @@ margin:1px; - Tricopter Yaw + Mixer OK + + + + + + + + + + + + + 0 + + + 0 + + + + + 0 + + + + + + + + + + + true + + + false + + + + + + + + + + + 0 + 0 + + + + + 75 + true + + + + Vehicle type: - + + + + Qt::Horizontal @@ -936,40 +1500,402 @@ margin:1px; - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - channel: - - + + + + + + 75 + true + + + + Channel Assignment + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + - - - false - - - - 0 - 0 - - - - - 40 - 0 - - - + + + + + + 0 + 0 + + + + + 0 + 100 + + + + Output channel asignmets + + + + + + + 77 + 0 + + + + Engine + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Select output channel for the engine + + + + + + + + 60 + 0 + + + + Aileron 1 + + + + + + + Select output channel for the first aileron (or elevon) + + + + + + + false + + + + 60 + 0 + + + + Aileron 2 + + + + + + + false + + + Select output channel for the second aileron (or elevon) + + + + + + + + 0 + 0 + + + + Motor + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Select output channel for the first motor + + + + + + + false + + + + 47 + 0 + + + + Motor 2 + + + + + + + false + + + Select output channel for a second motor + + + + + + + Front Steering + + + + + + + Select output channel for the first steering actuator + + + + + + + Rear Steering + + + + + + + Select output channel for a second steering actuator + + + + + + + + + + true + + + + 0 + 0 + + + + Differential Steering Mix + + + + + + + + + + + 65 + 0 + + + + Left % + + + + + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + 50 + + + + + + + + + + + + 50 + 0 + + + + Right % + + + + + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + 50 + + + + + + + + + + + + + + + 0 + 100 + + + + Front throttle curve + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 500 + 500 + + + + + 10 + 10 + + + + + 300 + 350 + + + + + + + + + + + + 0 + 0 + + + + Rear throttle curve + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 500 + 500 + + + + + 10 + 10 + + + + + 300 + 350 + + + + + + + + - + Qt::Vertical @@ -981,1488 +1907,760 @@ margin:1px; + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 75 + true + + + + Mixer OK + + + + + - - - - Motor output channels - - - - 1 - - - 1 - - - - - QFormLayout::AllNonFixedFieldsGrow - - - 3 - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 1 - - - - - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 2 - - - - - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 3 - - - - - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 4 - - - - - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 0 - 20 - - - - - - - - - - QFormLayout::AllNonFixedFieldsGrow - - - 3 - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 5 - - - - - - - false - - - - 0 - 0 - - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 6 - - - - - - - false - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 7 - - - - - - - false - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - 8 - - - - - - - false - - - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 20 - - - - - - - - - - - - + + + - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 75 - true - - - - Mixer OK - - - - - - - - - - - - - 0 - - - 0 - - - - - 0 - - - - - - - - - - - true - - - false - - - - - - - - - - - 0 - 0 - - - - - 75 - true - - - - Vehicle type: - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - - 75 - true - - - - Channel Assignment - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - - 0 - 0 - - - - - 0 - 100 - - - - Output channel asignmets - - - - - - - 77 - 0 - - - - Engine - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Select output channel for the engine - - - - - - - - 60 - 0 - - - - Aileron 1 - - - - - - - Select output channel for the first aileron (or elevon) - - - - - - - false - - - - 60 - 0 - - - - Aileron 2 - - - - - - - false - - - Select output channel for the second aileron (or elevon) - - - - - - - - 0 - 0 - - - - Motor - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Select output channel for the first motor - - - - - - - false - - - - 47 - 0 - - - - Motor 2 - - - - - - - false - - - Select output channel for a second motor - - - - - - - Front Steering - - - - - - - Select output channel for the first steering actuator - - - - - - - Rear Steering - - - - - - - Select output channel for a second steering actuator - - - - - - - - - - true - - - - 0 - 0 - - - - Differential Steering Mix - - - - - - + + + + + + + + 0 + 0 + + + + Curve 1 + + - - - - 65 - 0 - + + + + 1 + 1 + - - Left % - - - - - - - 100 - - - 50 - - - Qt::Vertical - - - - - - - 50 - - - - - - - - - 50 - 0 + 50 - - Right % + + + 1000 + 1000 + - - - - - - 100 + + + 10 + 10 + - - 50 - - - Qt::Vertical - - - - - - - 50 + + + 300 + 350 + - - - - - - - - - - - 0 - 100 - - - - Front throttle curve - - - - - - - 0 - 0 - + + + + + + Curve 2 + + + + + + + 1 + 1 + + + + + 50 + 50 + + + + + 1000 + 1000 + + + + + 10 + 10 + + + + + 300 + 350 + + + + + + + + + + + + + + 0 + 0 + + + + true + + + 50 + + + false + + + + Type - - - 0 - 0 - + + + + Curve 1 - - - 500 - 500 - + + + + Curve 2 - - - 10 - 10 - + + + + Roll - - - 300 - 350 - + + + + Pitch - - - - - - - - - - 0 - 0 - - - - Rear throttle curve - - - - - - - 0 - 0 - + + + + Yaw - - - 0 - 0 - + + + + Ch 1 - - - 500 - 500 - + + + + Ch 2 - - - 10 - 10 - + + + + Ch 3 - - - 300 - 350 - + + + + Ch 4 - - - - + + + + Ch 5 + + + + + Ch 6 + + + + + Ch 7 + + + + + Ch 8 + + + + + Ch 9 + + + + + Ch 10 + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - + + + AlignHCenter|AlignVCenter|AlignCenter + + + + + - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 75 - true - - - - Mixer OK - - - - - - + + - - - - - - - - - - - - - 0 - 0 - - - - Curve 1 - - - - - - - 1 - 1 - - - - - 50 - 50 - - - - - 1000 - 1000 - - - - - 10 - 10 - - - - - 300 - 350 - - - - - - - - - - - Curve 2 - - - - - - - 1 - 1 - - - - - 50 - 50 - - - - - 1000 - 1000 - - - - - 10 - 10 - - - - - 300 - 350 - - - - - - - - - - - - - - 0 - 0 - - - - true - - - 50 - - - false - - - - Type - - - - - Curve 1 - - - - - Curve 2 - - - - - Roll - - - - - Pitch - - - - - Yaw - - - - - Ch 1 - - - - - Ch 2 - - - - - Ch 3 - - - - - Ch 4 - - - - - Ch 5 - - - - - Ch 6 - - - - - Ch 7 - - - - - Ch 8 - - - - - Ch 9 - - - - - Ch 10 - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - - - - - AlignHCenter|AlignVCenter|AlignCenter - - - - - + + + + Qt::Horizontal + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Expanding + + + + 20 + 20 + + + @@ -2475,400 +2673,518 @@ margin:1px; Advanced Settings + + 12 + - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + + + QFrame::NoFrame + + + QFrame::Plain + + + true + + + + + 0 + 0 + 779 + 679 + + + - - - - 75 - true - - - - Feed Forward - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - QFormLayout::AllNonFixedFieldsGrow - - - + - + + + + 75 + true + + - FeedForward + Feed Forward - - + + + Qt::Horizontal + + - 30 - 0 + 40 + 20 - - 000 - - + - - - - true + + + + QFormLayout::AllNonFixedFieldsGrow - - Qt::StrongFocus - - - Overall level of feed forward (in percentage). - - - 100 - - - 1 - - - Qt::Horizontal - - - QSlider::NoTicks - - - - - - - Accel Time Constant - - - - - - - true - - - Qt::StrongFocus - - - In miliseconds. + + + + + + FeedForward + + + + + + + + 30 + 0 + + + + 000 + + + + + + + + + true + + + Qt::StrongFocus + + + Overall level of feed forward (in percentage). + + + 100 + + + 1 + + + Qt::Horizontal + + + QSlider::NoTicks + + + + + + + Accel Time Constant + + + + + + + true + + + Qt::StrongFocus + + + In miliseconds. When tuning: Slowly raise accel time from zero to just under the level where the motor starts to overshoot its target speed. - - - 3 - - - 100.000000000000000 - - - 0.010000000000000 - - - - - - - Decel Time Constant - - - - - - - true - - - Qt::StrongFocus - - - When tuning: Slowly raise decel time from zero to just + + + 3 + + + 100.000000000000000 + + + 0.010000000000000 + + + + + + + Decel Time Constant + + + + + + + true + + + Qt::StrongFocus + + + When tuning: Slowly raise decel time from zero to just under the level where the motor starts to undershoot its target speed when decelerating. Do it after accel time is setup. - - - 3 - - - 100.000000000000000 - - - 0.010000000000000 - - - - - - - - - MaxAccel + + + 3 + + + 100.000000000000000 + + + 0.010000000000000 - - - - 1000 + + + + + + MaxAccel + + + + + + + 1000 + + + + + + + + + Qt::StrongFocus + + + Limits how much the engines can accelerate or decelerate. +In 'units per second', a sound default is 1000. + + + 500 + + + 2000 + + + 1000 + + + Qt::Horizontal - - - - Qt::StrongFocus - - - Limits how much the engines can accelerate or decelerate. -In 'units per second', a sound default is 1000. - - - 500 - - - 2000 - - - 1000 - - - Qt::Horizontal - - - - - - - - + - Qt::Horizontal + Qt::Vertical - 40 - 20 + 20 + 40 - - - Qt::StrongFocus - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::StrongFocus + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } </style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html> - - - - - - - - - - Qt::StrongFocus - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + + + + + + + + + + Qt::StrongFocus + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } </style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html> - - - - - - - - - - Qt::StrongFocus - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + + + + + + + + + + Qt::StrongFocus + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } </style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html> - - - Enable FF tuning - - + + + Enable FF tuning + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + - - - Qt::Horizontal + + + + 0 + 0 + - + - 40 - 20 + 0 + 40 - - - - - - - - - 0 - 0 - - - - - 0 - 40 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;"> <table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;"> <tr> <td style="border: none;"> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD NEEDS CAUTION</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</span></p> -<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</span></p></td></tr></table></body></html> - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD REQUIRES CAUTION</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</p> +<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</p></td></tr></table></body></html> + + + + + + + + + - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 32 - 32 - - - - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 32 - 32 - - - - true - - - - - - - Send to board, but don't save permanently (flash or SD). - - - Apply - - - - - - - Applies and Saves all settings to flash or SD depending on board. - - - Save - - - - + + + + 0 + 0 + + + + + 0 + 75 + + + + + + + + + + 4 + + + QLayout::SetFixedSize + + + + + Qt::Horizontal + + + + 40 + 10 + + + + + + + + + 0 + 0 + + + + + 32 + 32 + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + true + + + + + + + Send to board, but don't save permanently (flash or SD). + + + Apply + + + + + + + Applies and Saves all settings to flash or SD depending on board. + + + Save + + + + + + + From 7a9835d3cf3c1b866465124cacd5c29fc0b54b0e Mon Sep 17 00:00:00 2001 From: zedamota Date: Thu, 26 Jul 2012 12:51:44 +0100 Subject: [PATCH 067/543] GCS-Fix compile under win. --- ground/openpilotgcs/src/plugins/coreplugin/coreplugin.cpp | 4 ++-- ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/coreplugin.cpp b/ground/openpilotgcs/src/plugins/coreplugin/coreplugin.cpp index 254f07865..6f6492f92 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/coreplugin.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/coreplugin.cpp @@ -29,7 +29,7 @@ #include "coreplugin.h" #include "coreimpl.h" #include "mainwindow.h" - +#include #include #include @@ -78,4 +78,4 @@ void CorePlugin::shutdown() m_mainWindow->shutdown(); } -Q_EXPORT_PLUGIN(CorePlugin) +Q_EXPORT_PLUGIN2(Core,CorePlugin) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h index 6c77ab065..8b41d9b0f 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h @@ -41,7 +41,7 @@ namespace Ui { class GeneralSettings; } -class GeneralSettings : public IOptionsPage +class CORE_EXPORT GeneralSettings : public IOptionsPage { Q_OBJECT From 4e96c743ba24da45bb0078d21bc4a8f02bc90a68 Mon Sep 17 00:00:00 2001 From: zedamota Date: Thu, 26 Jul 2012 13:03:27 +0100 Subject: [PATCH 068/543] GCS-Make UAVO saving code more verbose. --- .../uavobjectwidgetutils/smartsavebutton.cpp | 21 ++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp index 9b0268a4e..42a6d5e62 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp @@ -83,14 +83,19 @@ void smartSaveButton::processOperation(QPushButton * button,bool save) current_object=obj; for(int i=0;i<3;++i) { - + qDebug()<<"SMARTSAVEBUTTON"<<"Upload try number"<getName(); connect(obj,SIGNAL(transactionCompleted(UAVObject*,bool)),this,SLOT(transaction_finished(UAVObject*, bool))); connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); obj->updated(); timer.start(3000); //qDebug()<<"begin loop"; loop.exec(); - //qDebug()<<"end loop"; + if(timer.isActive()) + { + qDebug()<<"SMARTSAVEBUTTON"<<"Upload did not timeout"<getName(); + } + else + qDebug()<<"SMARTSAVEBUTTON"<<"Upload TIMEOUT"<getName(); timer.stop(); disconnect(obj,SIGNAL(transactionCompleted(UAVObject*,bool)),this,SLOT(transaction_finished(UAVObject*, bool))); disconnect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); @@ -99,7 +104,7 @@ void smartSaveButton::processOperation(QPushButton * button,bool save) } if(up_result==false) { - qDebug()<<"Object upload error:"<getName(); + qDebug()<<"SMARTSAVEBUTTON"<<"Object upload error:"<getName(); error=true; continue; } @@ -109,12 +114,18 @@ void smartSaveButton::processOperation(QPushButton * button,bool save) { for(int i=0;i<3;++i) { - qDebug()<<"try to save:"<getName(); + qDebug()<<"SMARTSAVEBUTTON"<<"Save try number"<getName(); connect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); utilMngr->saveObjectToSD(obj); timer.start(3000); loop.exec(); + if(timer.isActive()) + { + qDebug()<<"SMARTSAVEBUTTON"<<"Saving did not timeout"<getName(); + } + else + qDebug()<<"SMARTSAVEBUTTON"<<"Saving TIMEOUT"<getName(); timer.stop(); disconnect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); disconnect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); @@ -123,7 +134,7 @@ void smartSaveButton::processOperation(QPushButton * button,bool save) } if(sv_result==false) { - qDebug()<<"failed to save:"<getName(); + qDebug()<<"SMARTSAVEBUTTON"<<"failed to save:"<getName(); error=true; } } From 95fb9255cc29ead1b8cb45f37ffa12699678e1e0 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Thu, 26 Jul 2012 14:09:33 +0100 Subject: [PATCH 069/543] GCS-Made the buttons on the object browser smaller. --- .../uavobjectbrowser/uavobjectbrowser.pro | 6 +- .../uavobjectbrowser/uavobjectbrowser.qrc | 10 + .../uavobjectbrowser/uavobjectbrowser.ui | 232 ++++++++---------- .../uavobjectbrowserwidget.cpp | 34 ++- .../uavobjectbrowser/uavobjectbrowserwidget.h | 6 +- .../plugins/uavobjectbrowser/viewoptions.ui | 42 ++++ 6 files changed, 192 insertions(+), 138 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.qrc create mode 100644 ground/openpilotgcs/src/plugins/uavobjectbrowser/viewoptions.ui diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.pro b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.pro index 482573693..dad4e601f 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.pro +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.pro @@ -24,4 +24,8 @@ SOURCES += browserplugin.cpp \ fieldtreeitem.cpp OTHER_FILES += UAVObjectBrowser.pluginspec FORMS += uavobjectbrowser.ui \ - uavobjectbrowseroptionspage.ui + uavobjectbrowseroptionspage.ui \ + viewoptions.ui + +RESOURCES += \ + uavobjectbrowser.qrc diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.qrc b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.qrc new file mode 100644 index 000000000..e5ac47658 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.qrc @@ -0,0 +1,10 @@ + + + images/down_alt.png + images/install.png + images/remove.png + images/up_alt.png + images/trash.png + images/1343241276_eye.png + + diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui index 4669e7624..06d16d3a0 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui @@ -17,12 +17,48 @@ - + - Request update + Request - Request + ... + + + + :/uavobjectbrowser/images/down_alt.png:/uavobjectbrowser/images/down_alt.png + + + + 32 + 32 + + + + false + + + false + + + + + + + Send + + + ... + + + + :/uavobjectbrowser/images/up_alt.png:/uavobjectbrowser/images/up_alt.png + + + + 32 + 32 + @@ -42,32 +78,6 @@ - - - - Send update - - - Send - - - - - - - Qt::Horizontal - - - QSizePolicy::Preferred - - - - 5 - 20 - - - - @@ -76,28 +86,62 @@ - - - Qt::Horizontal - - - QSizePolicy::Preferred - - - - 5 - 20 - - - - - - + - Save to SD Card + Save - Save + ... + + + + :/uavobjectbrowser/images/remove.png:/uavobjectbrowser/images/remove.png + + + + 32 + 32 + + + + + + + + Load + + + ... + + + + :/uavobjectbrowser/images/install.png:/uavobjectbrowser/images/install.png + + + + 32 + 32 + + + + + + + + Erase + + + ... + + + + :/uavobjectbrowser/images/trash.png:/uavobjectbrowser/images/trash.png + + + + 32 + 32 + @@ -117,58 +161,6 @@ - - - - Load from SD Card - - - Load - - - - - - - Qt::Horizontal - - - QSizePolicy::Preferred - - - - 10 - 20 - - - - - - - - Erase from SD card - - - Erase - - - - - - - Qt::Horizontal - - - QSizePolicy::Preferred - - - - 5 - 20 - - - - @@ -193,35 +185,19 @@ - - - Show Meta Data - + - Show Meta Data + ... - - - - - - Select to sort objects in to categories. + + + :/uavobjectbrowser/images/1343241276_eye.png:/uavobjectbrowser/images/1343241276_eye.png - - Categorize Objects - - - true - - - - - - - Use scientific editors - - - Scientific + + + 32 + 32 + @@ -245,6 +221,8 @@ - + + + diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp index a2ca44131..f638e3e0e 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp @@ -29,6 +29,7 @@ #include "browseritemdelegate.h" #include "treeitem.h" #include "ui_uavobjectbrowser.h" +#include "ui_viewoptions.h" #include "uavobjectmanager.h" #include #include @@ -42,6 +43,9 @@ UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent) { m_browser = new Ui_UAVObjectBrowser(); + m_viewoptions = new Ui_viewoptions(); + m_viewoptionsDialog = new QDialog(this); + m_viewoptions->setupUi(m_viewoptionsDialog); m_browser->setupUi(this); m_model = new UAVObjectTreeModel(); m_browser->treeView->setModel(m_model); @@ -51,16 +55,17 @@ UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent m_browser->treeView->setItemDelegate(m_delegate); m_browser->treeView->setEditTriggers(QAbstractItemView::AllEditTriggers); m_browser->treeView->setSelectionBehavior(QAbstractItemView::SelectItems); - showMetaData(m_browser->metaCheckBox->isChecked()); + showMetaData(m_viewoptions->cbMetaData->isChecked()); connect(m_browser->treeView->selectionModel(), SIGNAL(currentChanged(QModelIndex,QModelIndex)), this, SLOT(currentChanged(QModelIndex,QModelIndex))); - connect(m_browser->metaCheckBox, SIGNAL(toggled(bool)), this, SLOT(showMetaData(bool))); - connect(m_browser->categorizeCheckbox, SIGNAL(toggled(bool)), this, SLOT(categorize(bool))); + connect(m_viewoptions->cbMetaData, SIGNAL(toggled(bool)), this, SLOT(showMetaData(bool))); + connect(m_viewoptions->cbCategorized, SIGNAL(toggled(bool)), this, SLOT(categorize(bool))); connect(m_browser->saveSDButton, SIGNAL(clicked()), this, SLOT(saveObject())); connect(m_browser->readSDButton, SIGNAL(clicked()), this, SLOT(loadObject())); connect(m_browser->eraseSDButton, SIGNAL(clicked()), this, SLOT(eraseObject())); connect(m_browser->sendButton, SIGNAL(clicked()), this, SLOT(sendUpdate())); connect(m_browser->requestButton, SIGNAL(clicked()), this, SLOT(requestUpdate())); - connect(m_browser->scientificNotationCheckbox, SIGNAL(toggled(bool)), this, SLOT(useScientificNotation(bool))); + connect(m_browser->tbView,SIGNAL(clicked()),this,SLOT(viewSlot())); + connect(m_viewoptions->cbScientific, SIGNAL(toggled(bool)), this, SLOT(useScientificNotation(bool))); enableSendRequest(false); } @@ -86,13 +91,13 @@ void UAVObjectBrowserWidget::categorize(bool categorize) Q_ASSERT(objManager); UAVObjectTreeModel* tmpModel = m_model; - m_model = new UAVObjectTreeModel(0, categorize,m_browser->scientificNotationCheckbox->isChecked()); + m_model = new UAVObjectTreeModel(0, categorize,m_viewoptions->cbScientific->isChecked()); m_model->setRecentlyUpdatedColor(m_recentlyUpdatedColor); m_model->setManuallyChangedColor(m_manuallyChangedColor); m_model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout); m_model->setOnlyHilightChangedValues(m_onlyHilightChangedValues); m_browser->treeView->setModel(m_model); - showMetaData(m_browser->metaCheckBox->isChecked()); + showMetaData(m_viewoptions->cbMetaData->isChecked()); delete tmpModel; } @@ -105,12 +110,12 @@ void UAVObjectBrowserWidget::useScientificNotation(bool scientific) Q_ASSERT(objManager); UAVObjectTreeModel* tmpModel = m_model; - m_model = new UAVObjectTreeModel(0, m_browser->categorizeCheckbox->isChecked(),scientific); + m_model = new UAVObjectTreeModel(0, m_viewoptions->cbCategorized,scientific); m_model->setRecentlyUpdatedColor(m_recentlyUpdatedColor); m_model->setManuallyChangedColor(m_manuallyChangedColor); m_model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout); m_browser->treeView->setModel(m_model); - showMetaData(m_browser->metaCheckBox->isChecked()); + showMetaData(m_viewoptions->cbMetaData->isChecked()); delete tmpModel; } @@ -213,6 +218,19 @@ void UAVObjectBrowserWidget::currentChanged(const QModelIndex ¤t, const QM enableSendRequest(enable); } +void UAVObjectBrowserWidget::viewSlot() +{ + if(m_viewoptionsDialog->isVisible()) + m_viewoptionsDialog->setVisible(false); + else + { + QPoint pos=QCursor::pos(); + pos.setX(pos.x()-m_viewoptionsDialog->width()); + m_viewoptionsDialog->move(pos); + m_viewoptionsDialog->show(); + } +} + void UAVObjectBrowserWidget::enableSendRequest(bool enable) { m_browser->sendButton->setEnabled(enable); diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h index 764ca2225..9a1a76d96 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h @@ -36,7 +36,7 @@ class QPushButton; class ObjectTreeItem; class Ui_UAVObjectBrowser; - +class Ui_viewoptions; class UAVObjectBrowserWidget : public QWidget { @@ -63,11 +63,13 @@ private slots: void loadObject(); void eraseObject(); void currentChanged(const QModelIndex ¤t, const QModelIndex &previous); - + void viewSlot(); private: QPushButton *m_requestUpdate; QPushButton *m_sendUpdate; Ui_UAVObjectBrowser *m_browser; + Ui_viewoptions *m_viewoptions; + QDialog *m_viewoptionsDialog; UAVObjectTreeModel *m_model; int m_recentlyUpdatedTimeout; diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/viewoptions.ui b/ground/openpilotgcs/src/plugins/uavobjectbrowser/viewoptions.ui new file mode 100644 index 000000000..bc2c1d815 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/viewoptions.ui @@ -0,0 +1,42 @@ + + + viewoptions + + + + 0 + 0 + 169 + 96 + + + + View Options + + + + + + Show MetaData + + + + + + + Show Categorized + + + + + + + Show Scientific + + + + + + + + From 3cb9d7029839180187e16301a25df193e61c26ba Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Thu, 26 Jul 2012 15:22:12 +0100 Subject: [PATCH 070/543] GCS-Made the UAVO browser view options persistent. --- .../uavobjectbrowser/uavobjectbrowser.cpp | 17 +++++++++++++++-- .../plugins/uavobjectbrowser/uavobjectbrowser.h | 5 ++++- .../uavobjectbrowserconfiguration.cpp | 14 +++++++++++++- .../uavobjectbrowserconfiguration.h | 12 ++++++++++++ .../uavobjectbrowser/uavobjectbrowserwidget.cpp | 17 ++++++++++++++++- .../uavobjectbrowser/uavobjectbrowserwidget.h | 6 ++++-- 6 files changed, 64 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.cpp b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.cpp index 46142340c..95288986e 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.cpp @@ -26,12 +26,13 @@ */ #include "uavobjectbrowser.h" #include "uavobjectbrowserwidget.h" -#include "uavobjectbrowserconfiguration.h" UAVObjectBrowser::UAVObjectBrowser(QString classId, UAVObjectBrowserWidget *widget, QWidget *parent) : IUAVGadget(classId, parent), - m_widget(widget) + m_widget(widget), + m_config(NULL) { + connect(m_widget,SIGNAL(viewOptionsChanged(bool,bool,bool)),this,SLOT(viewOptionsChangedSlot(bool,bool,bool))); } UAVObjectBrowser::~UAVObjectBrowser() @@ -42,9 +43,21 @@ UAVObjectBrowser::~UAVObjectBrowser() void UAVObjectBrowser::loadConfiguration(IUAVGadgetConfiguration* config) { UAVObjectBrowserConfiguration *m = qobject_cast(config); + m_config=m; m_widget->setRecentlyUpdatedColor(m->recentlyUpdatedColor()); m_widget->setManuallyChangedColor(m->manuallyChangedColor()); m_widget->setRecentlyUpdatedTimeout(m->recentlyUpdatedTimeout()); m_widget->setOnlyHilightChangedValues(m->onlyHighlightChangedValues()); + m_widget->setViewOptions(m->categorizedView(),m->scientificView(),m->showMetaData()); +} + +void UAVObjectBrowser::viewOptionsChangedSlot(bool categorized, bool scientific, bool metadata) +{ + if(m_config) + { + m_config->setCategorizedView(categorized); + m_config->setScientificView(scientific); + m_config->setShowMetaData(metadata); + } } diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.h b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.h index f744b4c8d..97ccbb470 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.h +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowser.h @@ -30,6 +30,7 @@ #include #include "uavobjectbrowserwidget.h" +#include "uavobjectbrowserconfiguration.h" class IUAVGadget; class QWidget; @@ -47,9 +48,11 @@ public: QWidget *widget() { return m_widget; } void loadConfiguration(IUAVGadgetConfiguration* config); - +private slots: + void viewOptionsChangedSlot(bool categorized,bool scientific,bool metadata); private: UAVObjectBrowserWidget *m_widget; + UAVObjectBrowserConfiguration *m_config; }; diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserconfiguration.cpp b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserconfiguration.cpp index cce3bee89..48fa2d73c 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserconfiguration.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserconfiguration.cpp @@ -31,8 +31,11 @@ UAVObjectBrowserConfiguration::UAVObjectBrowserConfiguration(QString classId, QS IUAVGadgetConfiguration(classId, parent), m_recentlyUpdatedColor(QColor(255, 230, 230)), m_manuallyChangedColor(QColor(230, 230, 255)), + m_onlyHilightChangedValues(false), m_recentlyUpdatedTimeout(500), - m_onlyHilightChangedValues(false) + m_useCategorizedView(false), + m_useScientificView(false), + m_showMetaData(false) { //if a saved configuration exists load it if(qSettings != 0) { @@ -41,6 +44,9 @@ UAVObjectBrowserConfiguration::UAVObjectBrowserConfiguration(QString classId, QS int timeout = qSettings->value("recentlyUpdatedTimeout").toInt(); bool hilight = qSettings->value("onlyHilightChangedValues").toBool(); + m_useCategorizedView = qSettings->value("CategorizedView").toBool(); + m_useScientificView = qSettings->value("ScientificView").toBool(); + m_showMetaData = qSettings->value("showMetaData").toBool(); m_recentlyUpdatedColor = recent; m_manuallyChangedColor = manual; m_recentlyUpdatedTimeout = timeout; @@ -55,6 +61,9 @@ IUAVGadgetConfiguration *UAVObjectBrowserConfiguration::clone() m->m_manuallyChangedColor = m_manuallyChangedColor; m->m_recentlyUpdatedTimeout = m_recentlyUpdatedTimeout; m->m_onlyHilightChangedValues = m_onlyHilightChangedValues; + m->m_useCategorizedView = m_useCategorizedView; + m->m_useScientificView = m_useScientificView; + m->m_showMetaData = m_showMetaData; return m; } @@ -67,4 +76,7 @@ void UAVObjectBrowserConfiguration::saveConfig(QSettings* qSettings) const { qSettings->setValue("manuallyChangedColor", m_manuallyChangedColor); qSettings->setValue("recentlyUpdatedTimeout", m_recentlyUpdatedTimeout); qSettings->setValue("onlyHilightChangedValues", m_onlyHilightChangedValues); + qSettings->setValue("CategorizedView", m_useCategorizedView); + qSettings->setValue("ScientificView", m_useScientificView); + qSettings->setValue("showMetaData", m_showMetaData); } diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserconfiguration.h b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserconfiguration.h index 8e31c18dc..cc5317aa6 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserconfiguration.h +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserconfiguration.h @@ -40,6 +40,9 @@ Q_PROPERTY(QColor m_recentlyUpdatedColor READ recentlyUpdatedColor WRITE setRece Q_PROPERTY(QColor m_manuallyChangedColor READ manuallyChangedColor WRITE setManuallyChangedColor) Q_PROPERTY(int m_recentlyUpdatedTimeout READ recentlyUpdatedTimeout WRITE setRecentlyUpdatedTimeout) Q_PROPERTY(bool m_onlyHilightChangedValues READ onlyHighlightChangedValues WRITE setOnlyHighlightChangedValues) +Q_PROPERTY(bool m_useCategorizedView READ categorizedView WRITE setCategorizedView) +Q_PROPERTY(bool m_useScientificView READ scientificView WRITE setScientificView) +Q_PROPERTY(bool m_showMetaData READ showMetaData WRITE setShowMetaData) public: explicit UAVObjectBrowserConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); @@ -50,6 +53,9 @@ public: QColor manuallyChangedColor() const { return m_manuallyChangedColor; } int recentlyUpdatedTimeout() const { return m_recentlyUpdatedTimeout; } bool onlyHighlightChangedValues() const {return m_onlyHilightChangedValues;} + bool categorizedView() const { return m_useCategorizedView; } + bool scientificView() const { return m_useScientificView; } + bool showMetaData() const { return m_showMetaData; } signals: @@ -58,12 +64,18 @@ public slots: void setManuallyChangedColor(QColor color) { m_manuallyChangedColor = color; } void setRecentlyUpdatedTimeout(int timeout) { m_recentlyUpdatedTimeout = timeout; } void setOnlyHighlightChangedValues(bool hilight) { m_onlyHilightChangedValues = hilight; } + void setCategorizedView(bool value) { m_useCategorizedView = value; } + void setScientificView(bool value) { m_useScientificView = value; } + void setShowMetaData(bool value) { m_showMetaData = value; } private: QColor m_recentlyUpdatedColor; QColor m_manuallyChangedColor; int m_recentlyUpdatedTimeout; bool m_onlyHilightChangedValues; + bool m_useCategorizedView; + bool m_useScientificView; + bool m_showMetaData; }; #endif // UAVOBJECTBROWSERCONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp index f638e3e0e..5ab8eba4b 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp @@ -66,12 +66,22 @@ UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent connect(m_browser->requestButton, SIGNAL(clicked()), this, SLOT(requestUpdate())); connect(m_browser->tbView,SIGNAL(clicked()),this,SLOT(viewSlot())); connect(m_viewoptions->cbScientific, SIGNAL(toggled(bool)), this, SLOT(useScientificNotation(bool))); + connect(m_viewoptions->cbScientific, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot())); + connect(m_viewoptions->cbMetaData, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot())); + connect(m_viewoptions->cbCategorized, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot())); enableSendRequest(false); } UAVObjectBrowserWidget::~UAVObjectBrowserWidget() { - delete m_browser; + delete m_browser; +} + +void UAVObjectBrowserWidget::setViewOptions(bool categorized, bool scientific, bool metadata) +{ + m_viewoptions->cbCategorized->setChecked(categorized); + m_viewoptions->cbMetaData->setChecked(metadata); + m_viewoptions->cbScientific->setChecked(scientific); } void UAVObjectBrowserWidget::showMetaData(bool show) @@ -231,6 +241,11 @@ void UAVObjectBrowserWidget::viewSlot() } } +void UAVObjectBrowserWidget::viewOptionsChangedSlot() +{ + emit viewOptionsChanged(m_viewoptions->cbCategorized->isChecked(),m_viewoptions->cbScientific->isChecked(),m_viewoptions->cbMetaData->isChecked()); +} + void UAVObjectBrowserWidget::enableSendRequest(bool enable) { m_browser->sendButton->setEnabled(enable); diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h index 9a1a76d96..510dc8820 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h @@ -49,8 +49,7 @@ public: void setManuallyChangedColor(QColor color) { m_manuallyChangedColor = color; m_model->setManuallyChangedColor(color); } void setRecentlyUpdatedTimeout(int timeout) { m_recentlyUpdatedTimeout = timeout; m_model->setRecentlyUpdatedTimeout(timeout); } void setOnlyHilightChangedValues(bool hilight) { m_onlyHilightChangedValues = hilight; m_model->setOnlyHilightChangedValues(hilight); } - - + void setViewOptions(bool categorized,bool scientific,bool metadata); public slots: void showMetaData(bool show); void categorize(bool categorize); @@ -64,6 +63,9 @@ private slots: void eraseObject(); void currentChanged(const QModelIndex ¤t, const QModelIndex &previous); void viewSlot(); + void viewOptionsChangedSlot(); +signals: + void viewOptionsChanged(bool categorized,bool scientific,bool metadata); private: QPushButton *m_requestUpdate; QPushButton *m_sendUpdate; From 0f8643222480df415f347be7973223d41af92872 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 27 Jul 2012 11:19:41 +0100 Subject: [PATCH 071/543] GCS-Added missing resources to the UAVO browser --- .../uavobjectbrowser/images/1343241276_eye.png | Bin 0 -> 1731 bytes .../plugins/uavobjectbrowser/images/64 bit.png | Bin 0 -> 3307 bytes .../plugins/uavobjectbrowser/images/down_alt.png | Bin 0 -> 2256 bytes .../plugins/uavobjectbrowser/images/install.png | Bin 0 -> 3567 bytes .../plugins/uavobjectbrowser/images/remove.png | Bin 0 -> 3577 bytes .../plugins/uavobjectbrowser/images/trash.png | Bin 0 -> 3657 bytes .../plugins/uavobjectbrowser/images/up_alt.png | Bin 0 -> 2208 bytes .../plugins/uavobjectbrowser/uavobjectbrowser.ui | 3 +++ 8 files changed, 3 insertions(+) create mode 100644 ground/openpilotgcs/src/plugins/uavobjectbrowser/images/1343241276_eye.png create mode 100644 ground/openpilotgcs/src/plugins/uavobjectbrowser/images/64 bit.png create mode 100644 ground/openpilotgcs/src/plugins/uavobjectbrowser/images/down_alt.png create mode 100644 ground/openpilotgcs/src/plugins/uavobjectbrowser/images/install.png create mode 100644 ground/openpilotgcs/src/plugins/uavobjectbrowser/images/remove.png create mode 100644 ground/openpilotgcs/src/plugins/uavobjectbrowser/images/trash.png create mode 100644 ground/openpilotgcs/src/plugins/uavobjectbrowser/images/up_alt.png diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/images/1343241276_eye.png b/ground/openpilotgcs/src/plugins/uavobjectbrowser/images/1343241276_eye.png new file mode 100644 index 0000000000000000000000000000000000000000..72edb6b701fb7deb90d293ee71e3fab6e58b949b GIT binary patch literal 1731 zcmV;!20ZzRP)SY?GQ5*WMs8k7o_D{R6ty)bRsA{)$TY*WdG)<~hsp=jex)s_C zC{t)lK|miWw1}o1qyz{~u@k?a*N*M`+PRJ+F$7w>{edQNrDK2o?svZPJLmk)cRn-2 zFmNp&4%hg(4&XWf_EkWRKD%tag~Oe+x=Y~MH?Fpj3hJV!8^;w5{}_J$i|sU}|1SW9 z1JCvCbh&KzH#Ruoa5-QTEfB4uY3hm!N>xFrSVloEp^z&&M1`qlW4>6P|%0I=Pg zde#+Xr5BArZ|Y951f9 z_qS*EUkUl;0JuF*_ipIxZ26O}%ZNuNQIhlEDUhsv5YfgV{NeOcWOzU9yaJI^py?V) zRfeL%!);Npd6fZwc0cl`cY&*9(Xz0e0JS0!p4=+83^Ek?+3wg79@*0UKl-tr-u9C z^|(eebut<`g=$%bpc%*v{06iA zn`*h=b0UIxE{_gZ9&PqC!iV0(#Nl`G(Cw>{&m^Jo2Flecy8JG@c60)__BVlZEk@HV zKP4)vm_Gh@IP6N_x>X%FZab71nJ4Ic8Co71bR9`2&JngM%`!~i@&-!YVe+_)MFAg9 zUd*G#Hs}51p|_Avromfn$P|j03Vn%*lP6FvrJz=2d@wPC7Iy<|f%SVQKC|S7$qx_4Q#vOEW6uog`G@ zwpNgdCcp^-c#=pYjASZ-(D@JwnHVzJG!)v$DlkZP5iX~VoKWDoX+1iBG>)pGz^+Zb z^2f&mJ*I6FfX(MtM?|{=4oO1jo4ep&u^QdoOW|->VNm!OMavWmrxNkhI&~NX0`T5@ z?;{qCAs$Z>#brSadRvRf@s>04D9ya5jq@jR6shh#E|=ro1g=fZ+XFLEU} zoHl8WU}RV~YC(op0|PkaG4y}y4ouC+dx2@2`Boo#Y~O}jol{2qXSYB~9)!VJYZ+pu z?}Q-O-->LRN2bCfc*nQl^+`llg>tSU(CWs}J>Nm0YDKOh;I@IKb2Uu?Hq*q5Jh;>t z*uk|>#(s|-dp_QJ^TTgHV^)J1DLpM~NKV91X%qTsVa{jzqUS^IFR6 z5fKvEw9PI#kenoK+a7QK-O66+&IOBl!1LxtJj%Wyp!p_Qte?6K!OiO1jHU4iWVZBjMa8Y?@tT66$N*CK3)YZB0=TJ*&Xk@@(BACquLvTW6 zRx&1%0tt;U{>INx)rgnad$MYLZ;`ItK22$IaIEDtmFUTVb}kfT?cTj0sKpV Z0RT&Hpm`Jl8sPu{002ovPDHLkV1i#rJ7xd? literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/images/64 bit.png b/ground/openpilotgcs/src/plugins/uavobjectbrowser/images/64 bit.png new file mode 100644 index 0000000000000000000000000000000000000000..749b176201cbdf03dcac72ca012dc819a2158920 GIT binary patch literal 3307 zcmV

5Q;P)4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w2hd4GK~z|U z<(6w~9Mu_ypEEN%d$srCti7=l-(pCW1V|l;mI`7)0)$&i)e@>y^ri?JM5zibDxv~H zsgT;LC=v;@f|5!tASL2bXc8JoLU7e4Z5#uFB(>u>4R*Z7UVCltu6Jk7IsLKgjU79b zR`gdt>CJr!DOVTU7=b|hK|ENE2KOIy873lcsT!O?f$n@DvYQp%YW&e*u=sjQH8 zG_Hd6jiPqx@_^QwgO5G%_MK_D>fZuviSod_i!b}Z)i>P`aR&!LYlP2_Fio_SP$-~s zS#&mo&gVf0L?D3S4WAlymLUClAv^x(>c@MAWWYJ9%p7 z3mX~Xr*k^6HEeXPdSY8s+!;4zYPh)4Pa%Zm!HmX82V?5>JHIYsBd%v1NSNlp?JI7& z{G-Lq@e9^}%|z=@Mflu^2w@~&J(%t|-g6m;Uu}nJ4ul_m|Iz!t5V<{~CgUHba%A)F zjLET(O-mv~EM$|KC~&Ad#rdKx=ErZF0Q9ADqGZS#tZi14yILS|O#zaU?d0;kdhqA zxFG_-@OYj(u31D?g|}SvjduokzWvk;CvIzN1mMWY5z^VSe_ux`3a-Qu;7UbaDn~0l zG0Oq1>Hd3PW@J}KAHUy!l7;gE08~|YsjBeuPVd>mt1n5=5D&6#Uk}^%_0SLxvT$C2 zbkKzIfl|vxN6PQv3kc zetQRzpv}=C*AU1(vmB7gq1~OyOe_)csnbK5a)C(DE`DI9XPMd{9JKi)QR(-Pi1<`z zG82=@q203_;F&e4%=h2kse_fDs}B2XcXsr1eQPb>xU!i|JKkqB>k&@} zuMY9M1HAx*10FhlzJ|xY*-FRHuA!mSoSS!@0Mi8HoHVWCnP94>X%Y>2sjmsK|8&-C zsr-}EHD>_0n^*7Y8chE!S`|zVj81a*vqwm09UA5Zxcj=6viKt}9cS~OdJ(2ID=|zE zX1S){=V4(yL^Kv0?D}Y|!`-}k&veb%{krkBwN*ar`CFF8jlUcp@r~ppS6@^^ecVqv z>+(uRlHQ@o(rj@~iQ-!^;gJa|9sn>ly!_~8 zi^3b4Dl2OapB$raG*8X}g)UB+YQ%CwPW|e#t$q*Gg>6~fbMul4w+P)CLzB?UDU@V4Pm6t zC3nAn=0)}Nm+zTNYfbrT zJ=9nEX>F`zEIX8Z`S9r%73L#!Zl9P-=ez)PZlBN>e)X-c!PEk+a!o5QNSKz#vJ4?W zPz2Bd!!Yn#29bb=+K876=LcwA=*u5E)|Gzy*x(K|>AjEV)}8nCGG`B*`;4*vR}XnD z@BLr-eDhc+P#x<{6^!I~flOWj5cHbVRC;KNdDTQFncDu>p31zNe@s1h$0nv4<39i} z01w~;ft}7PsA6QB}8g<%QMRrrKJsV}|@7@W}Dp$^QQQfqx7J#)td z(|zD1kOL-w43Gu#6c3|isJQ^lY2pzeR)X*YUSjo8W9f}6b*y=1L!zn*;MBnIut@bB zQ18CdPP%UdC;*cs;n7l#m98bAJ`O;X9GG$;K=Ax002ovPDHLkV1jJ2ru`EP)4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w1GPy+K~z|U z?UvtbTV)u>KRI2JwriH1IdN7u8DiUXsUqT?BNW9uuiU>NbAq5Zq6~H+2!(>8h;!;D zc;m%zcOndQN!y9rItR+wmA1`kv$k1n(!`VVpYuF# za$fj<{l_a7RXF+1eIFSy<3v=w((3f3lN+z}1mL+TGo4DLE9YK*8&|A{>XY#U9DDb5 zzCBqE_1_f*006CNh!VC}440xn>qxed0kqaAB~eO*YNeLwUIU;(X^GI`07^-Smj5?8 zpfpnY2JE! z_)>t1l#dZbbpAY2Dv6K+Pq?8ah>bF>_%!ivA zM(+WdzXFXX!i|O0|9k|wSNl&9GfrS|005<_In_u2HKz(nlY4EjDb~7=#Qtkf9NsJUig~D z((2Lt`;EDFZC^Ko;&saVGp@e1XiXkGn8vEyq+DOY@g1Zhv>e~1VsB7$t0enOzWQdK z#ii18;Y0UqXI57LfTej^FtftAU8?7v96LhYuiy#~sha2OUZr)6WPFH+(pfI$ixi8u zrwbo@ceVeX007oCkvETc#@ec#dtx+0-K*jV7pe5NPp?#r#I7M8PG>0;EQ-sk(=%tf zhlc_HSo1P(W;|nk)y_RWnxW=y1rXiClkpUX_D(Q2Q^ZPxH^&^~ z&YGQ@7#pYV{RPq9_JKr-N6aig%r3HItxnB-=D!){9SH!y`cdW0jB9L`?Ob+bj4iK< z2AA@(nd>9&W^|8_qM?%s2|oA#;SQgdh)4f`R?L1mKMrqu6(IJ08&Bi2Ks?S z8%Wo%&SlX2i|!9hI?ei8PdM?s@#5ZLUaFM%^yiD}0w8H#MFijjF7P{02Wo&5?CYSq z0>lD<1TX*$2I0w|EA8zyg3mHAYyrps!V5y}pxidiwjF5gw+Hlf?8Ufywz{KKTgkTI eh!^&MY5f7RH%44Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w2-HbLK~z|U zm6v&JT*V#7KQr^*+r#TUZPz%5b0`oDY6&h9O;w3fN@=D1!C?uh6>UWuDpe?@Dn}`m zxB{h8MG;jh(NJh`5X6yanv^R+YLt)?ND#S*bJ#eEe8hI_^?KL#9y8NF_U+nhrk?qm8no7c z#+Wj1O!30hRQ|2?>wo-7<#eaQbaZs6M56J9&p$tT?F%pbp>E5Tt<%<)=gQP#tpzN` zSpT~`UYVQiU<_DWUVHrb5w&U4i{A6kZyN9KKYvq4N5?n1y1F!gr~uf#d-u|0vT0|r zSom@>8Ryigv$(E@5CX?hghC;NkUYI}9sjL8c&6=+gi9~!2%-(L|VxBvH&|Vdqh$d)= zH}Jb>-XIdG_XQe^u~q)<_x2-%M=%(|7~y8K`3B%TfUF!83b{?zIv&8(RE|(6*7kO8!G2i0Z6G+LI~IThA$S23xrpk zuvjY32_Zm$qg>xP7Ya8<6N%K3PETNrK`G^Gtx^k|PzWa_gmA32ELyafXf#N3b2F~% zmIYPTA$-r7bvPvy05{&)PN7iX(BaR}MN>6FFc@HBB7-p+YaPcJyAS~ACLx4pjAhlT ztH@-gnV9%uo_ANm!iVAm!Il9YIB=L!sl@d36t3%FjKNwkhXc(;xQcBO5Qquwe zQi^&ht(q^ea?2`@t!kheL_V3B$ul*TB@_x)&1S777zmKbOro_$O6yoFVwW+2Y5?n5 zYib2r%h1puN=c&8Sd9iMl0`L|HNjw@M!2<>y1Fpg+?1b;tgE$6E&yPRO;{`4xq^Fp z&k_sYqk7G;nEQPzs@gq6J&0F}ro+fg>N5FiD)=`2`_5CRJnbRK{w-@LQxQQy4b9&Tv)&Kxj?QmKS7#C!TnkYp%H#Aq4wR?c}}(?%>?u1xh+ku{6!4$&ooG zu;lWSJof7!lBi2iABf_qC_nn;uUPr*>xczX7-I>ALiF^UVe8gc#kzGJp^lDw6J1>| zk4b>>@$rN))?K!&l`UJg5D0j_O3Uio`|dHuvlE;iI78n^AG!P#v(6wW=ow1nD3}R~ zHpj+SHv>xkcI@~kp-^2liEO-Q z7u{!jC=G?UBHoOWPSp>rEnCGJi!c<}aDIDF(7fn18lXd_B0KXS@SP{JYXh1v1m zAwK)$7{B=LE7iS~E~Vu7iQ{NpLMg`uF{=Smgm^F?^9x? zg+yH(>1T1NB%wf%1OM(}-`+!Pxb3es!sqhS(>Y2djS#|>l35J^jgBK+V+wk$H&JJ2(&KYIF1XV zu?oN#8?zRrwPEGTmGt)Y)f`kRY4Z6Q5?(87SKQ66T_4j_w}LBDix}sv?e2xi3%3A3eW4QUIo0-;)4wwIrp)HAZ8MrM@oAbY_xeZC6rX7v$Kn z6GS2r8XFriMl(5?rBFyJr%wzjKjZ(qZ~gC8?6Fi1L`CYLKmi8nW(%A=d3HgPsuZA= z2dB0moh{`nZT0Ha+w4+C?)ZMRt?erWgCUL_{eeV0(f44VyQ$=&shcs2U)sgDNRkyM5FN<4TM4=GMO~taQLzmV9DYo^#1KNGMO~W zQ3Qex)6-K#B5}sX#>&Oq(xoe3@;vWerIeIXF0kX}no<%eRW%gn(_*n$v)*wW;_(E@ zWQud=zR=lh_Rl>%-S=0#s|{EK!~ipAU#0Y|pb_)NE=T9@tzrf|AOLg&2Z6!Lf`H%U pyiNa4`(OJi^;-qRG%yL|{{wO?ywY;``vd?0002ovPDHLkV1jq{)N}v< literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/images/remove.png b/ground/openpilotgcs/src/plugins/uavobjectbrowser/images/remove.png new file mode 100644 index 0000000000000000000000000000000000000000..9aef8c8ab89ed7a4a8f01b50b1b022ae52f47922 GIT binary patch literal 3577 zcmVXwP)4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w2;NCVK~z|U zm6vO5T*Vc~e>3;753kp|>rF6rZ0A89bpm;q01cw0pceWF5(rn6wxWO<_(G$$5+F!h zD4~dmmPSY^r9o@=j4MgE0!F%78&B zP)Y#`t-Z0vm<((a~WglQT9RI&^r+#*M$M*|Mc;!Wi$JCk@6J zz@WA9pS}6YyYn5i24lRn2M_MIHf?&&efHT+!)MN%y1t{M?mxSmUwUyIfntu^Jc!WfN| z5@Wy^jn*Y*&u(RKFvrQ0Ck_k__O4#LcI~Mu4-5|%Q}y-QP9#$7-o2aU%daFBi}@Zn zzdNlp`?q(p`}qxg>*_D@#|`WF%DN3Sulyof8{eR=8o&ML-3Z|l4oA>hIQe`b4V(f9 zwiJmtGmWubfbsD$B9Ta7aB4rY^9^=CzkxfKt|a`Q6WrN;9e-K>AOpugL2KpnLRXDL zj>}LcgVq|y!I4s>D|Q0_QmT3(gk$``mrA8+#(VzxSKfVQ9k*QG&cw-MWctt09IxTl z_G@|L$M=vQ=$mF-Yeg(pLpD2t)*8#Q9Hp%KX(SZFt`|bs#u%EKW)Y8vX=rG`aU6sY ze0Jai-umeexOv%?(AUGncn+teDXJn%(w8uK<-E|XRSh5^v=rm)a!#H@JQe{oC zG|9CMbC_6B;76AwS^c{=aU2`1HO3gC(I|aq`%y|GrF69}&%8(oM6Hy@svI4!dpqd5 z>n4^iTta-jpV8a^+IacE2oMsCDpM+q^VPX4xN6xFc6|RERiO)qLgaFzD5a3n*v5#u zX#j+<(qLR;bQSA2-?Ea+TIbP3p6qZRx?B!&gD_qekW!$Hp*%UsH!uG(S1en|YxjID z08mpCB|kRqCnMu1Wm3}sXl;_lNN4KKyStA8@b$%Q#A@oev}pn9hB<_ssIM)+7^D+M z$6|;?5@K<_ck_J!Obqq;*$|3_fAl4LU8qcKjf-4YlGyn^*c8biN?rFfzf~l>4ZE_{r2^M zcvB5)ZHPo7bax-4tLyh-_3DmDN5{R%ZQEYVNPywt;iT5anLWFeEnBt_3b`J`FLI{A z&;AC45Izxvzh3!UKbrFtnX#~4lj z;J`HF6}j)j4*}t201@0{UMPUAuWp~FQ|VGl4t{bFrOH^A?SQBcNN9{s`|M6R+_`>= z#UfJ5DaxK(6Nv<10uKlwJSzL#Xu7nKVzD^w_B6(j&1Mk@lqzG}wgX~D5CW}DoiSKS zY39wFN6*QVRW2--6@|hiLqkK}*>zn1zBd>Rs$2pflgUsjm8Q90Yt7M5k1%KMTt63R zTWgaD02m|cjghX_nj5aafe9rk6brubGKE5cfq?;z9621s{gMTjlU}^kV}Gdtz^PLw z$>;M`hK(^;mY`THuwecoADncIQK=vVO6im_IF-EJG$V}@t;H3J{OA~^Qi*IfOJ83v zbE6J_>N&)Pts&}groW#=B1tF|3Ov->+Dtl~;>?+IL5T)9TFdhQj3Ff@jz>O2ZB3Mk z+$gi#7EoIg=Hrh)Ar^}}PiM@sDhShHr0V+?g#>#BRewk(bu`jlicPFvgOXm4N6o<0Ajx3`aM zHp|$UcUq*ha9x+$+8F6{nmKc3vtq?EGMQoCd+#6g^qit{!BvV`&jVIndwaWMH#Rob z31RG`M-TJji!boR6Hiyga9|+A*|P($-k?EiB6-mm6hpaEP;K z&(Ybrjchg-q~QtxfT5v&cI0#{%eGouTTEByOXAq^(^Jyuc{bC=*^fQ;Q15+f?w6}R|A4S8mqiQb zQdSDBl%MRp^B!cq;9tR1$@BjSQ|G4sQ+QHJ$z)-Y-rkeq%{O1}6M%3WH+%bS-;TGn zEhQX|u>ZjO^!toX)Fp|>6GWpmxUP$o7D5Q5lsx&=!>oJcX`XoUL4NY+hCr_W#X~&u z@KaT%q)?bdYfXK9l7H>_JKJ9F%#}*TgbkS5+FFqx8)YOn%w%DLUGKh4O*F==<`!(* z1}P}35{~0yS<(k!5s5?@$qi4F;c$eJ+%N#$J)d&(lRxL+rp*W;a6=Yjiwc zUOf!4l3Xr}>xOXM5T$aN?(XCC_4U!x+``P64aDP#Di1^=5puaK(P;Fd5}4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w2`))QK~z|U zjhB0HRMj2FKlk3nkQgGEViSx31){tx3Us8M@liVnRXfE_9Pq!k z(?5_}KxSI3Bsg>&%d}CaB2cUWQA8}pKrD|y2ziiAB#_r;AIU!Mz5U}}W+L6FXXehi z_nfom`#rzk_xJmq6-eC#K$|+SdGlt!AP93rQLGdNAy1N|yKc>CFq%vz&#J0=-2|7n zzVgcP@7izb#I$Ym=FPQMtMze76jus@ke!p0qqtnzPDN1=1&L5NgrX=oolaC$A(2Q# z$AV+=>tBEEv^yMMMIw+*?zVIe7hg?ELu) z@uZSGo=7A%Zr!?d@H+|A*Vq3^mgQ#`FIsGBztkSQdE-X>!o`b;fq{WnPoF-$9oPr- z0lx*F1C{`r06(w=*s*ETrg$PA-|BL?=Fjq%CS|K^J%9dOTv64=ZQHiJFfD=l`g%{A zoOapk^;)i7>mC21rR5LJ&CQ*_S-=6510BE!a1SsJTmohRS-=^ip9P!;!W%Yh*qxV~ z`_RJ=KVms{tT{M5GQ48fu3ews!W5?xFqupbyId}zx3@>>xN@bexw+W}lmT6U4_E{Y z8NXWwn1Es6e!vZM8zk=s0)VZtv2pPF;NUwgEvG|8g+)%QEI3Mx;5Wd7z(QafkPW;F90FQ^9fo^;H)F<(r;EMb#}+>D zKu&skdQnx?e0y8l8ATI>v1wfZ@Y0qo$>qyeO8NQuT)Nz@UTSZT27^JXs%c$jNoqR& z$tMev$>hl5#f$%X=+L40CP`W{@1A@1gu~%GgTdgsdGqFlEoQS@5ClhQS(!Fx&RlbP zdOD*cV;nyCUSvEHsolAA=U3AbSpW3Xhwq$Sv2@j{M@)J7c{rUJL?RKoySwS>>7l>B zKN=2&l|&*TO-@c|R;x`F1VOUf?NUKuf$a17m^pJME|-gVJWePSW^8PXqs`4~XXlmE z+js1^Zz`U2JAt!pZGG;dqUvC9EW_jWm|ZRxvMl3tI?2t=qoAPBoS$DH=jP;@^YaTV z1$Pw6#eToJtgOuBFDap@s1S$4fhdY7ib60Lgt-f+S#cFgF!ja-+%nAx8B+Zw4z7Rw-RsztAQtg!!vOR{LR(BX1>;YZ}EWqQyztDYJ zYglKoLGU230Z2nnR0q(LRs&F<3MiEYFn~tU73(!N{}4z3KL9>LH-8z>gRYlq!vZJK zHBoL5u%qiLoC+wFNhI`~?=~Jgu-E99p$jSmJPEX+`+6M^0saa62)#1ChaS?)fOd4N zUHU#25YYt)kZ!O~7zFas#b!3%Wn+Clx_C9?-DRwCpld@!*UI;9#lQ)m5nW*Wfj5m! z*8^Xo3-m$Y6uO^_jPaiXPT(D&8F3=IvjX7%b5XU?9bwYBy7V{6y`dSGyHMdRMRC90}6w70jr z02Sy@1(Zqy0+8nMc%CaOEBmP|%T-T3^%SwmNt%xyW$l_ZWM^mdxBdIMd+uDStE>4( zQxh(ii)Blfa^S!LuJ!e?WXTd*T3Yz{`0;_Hq8z$-@#3%0L;M>pl?F6mV&Q@XOFeFP zmD}ycVm2d55+!~=Sy@@cVllj4FEhMeR8=J}H<#k#V&d^Qc83GM-%pw>qpB)?zrS$d zf(09!nwpeU7MLy!vD@tr+S1ec$+~qkG&Iok_S>vqzn)J|o}~W87g_!2qYMuXvHqE7 zsI06cHz$WDo_vywj0_%GwTeG(-%f8&4|R2QsH)1jbLVD%Ul#xf4SO0wk!U2nsIZW$ zSFbX6?pz8A3i#~QDN6i)3JMBnYiq+|u~1oANo#8>$z+m>iVC{ByZP_Ab5zWpO4i;BK;gFk2h)Y2In$XHvsf%#x_p_Mni@n=WarME%(?3>d_Etqz4jU!P+MEe zzJ2=`9vNZf%9Z^4!w>oF)G2E2y_dc~0JBBLj^NV=

MZ-`rsgmcpQ(%gQ}|ZUb{v#8fE6pnG_cnV^4R` z+1VLb`{Olp(W5J2SV4pT4@1Eiv);Hl7;t-voIamVtg5O)ltcyw2I#olK`=N@hSR~w z$S9*Dqs;JnFJ&HOrNil_i-iW@K5$;mE+{av=&5vL%hef+F(s^KrY~l$DlJSXhX~VnJ0^qS2^! z>hn`Qe|dfP`+-2qfsU% zCP^d`2!ent%h+r-Y&IJvlS%FB>biO0z=4i!+qRwFz5CD2fk5E6s;Yyj2&B@03B8}*?kdAUz$t!4mB80!?{v~l#y%`N|{ bQ^EcRh_Zb2PbzPo00000NkvXXu0mjf6R`eK literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/images/up_alt.png b/ground/openpilotgcs/src/plugins/uavobjectbrowser/images/up_alt.png new file mode 100644 index 0000000000000000000000000000000000000000..4d8b67f59d048a2b0082852fa31b6ef927e6479e GIT binary patch literal 2208 zcmV;R2w(S!P)4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w1BFRMK~z|U z?Uqe%8&wpBpBcy4vD46o6aq;Nr7B}tvoeEDnUez3?mbx9nL6{ljskzS3?%)R$K_q}IE z1OLY!WAqz5dzrtd$%#+9-m_OaZ-)}T_1yK+ua6ZVG0~kp6*~6$XBXcmm!Es1BUHPAA;F*GVrb&pV0pgkN>??ht^p#`^#eHnK zjyB2+hR-l_f9XPdwCvB_Ed8`E0P$;G*@3=L`pR$$sTUElfYJ)7EHq^XUph-}F&_&= zEB@S+I|$bR@oQb#f!y0q3?4trTz)y$9xeKFQ{{#bt^nen zbY;WO^rkNlk6@|!n&P@fn-Ef$cr6@dF8_DTf4bzKy|p_;Lx9A`o$3B(`!esOhN;MT zEKxuziBf7u327m8iSywI^UJF--|02~>@BM<#I68|4?EIFpF5HrOC~9cdsM^*Qp+vd z>!}KHE*xPYzZMIeDg<*sSAJ{?An`#*`bbZ2c5Ea`N#3PmZ=hThe*{7mcr_g1ucg(Y z;E7@|cY8a;jsQdBzT+?S^nE*i>1{lwz%+cA<`dY$!jfgAQoG7yv=i_h#_xR!ug6d9 ztvE6vnoq3#A70&EMVv8A9Q?1n>a zDL`pg%Qgidq;%zgkh1jvT4@&6?l80Td&99_kBM%%16m`L#*&Q}7D|I|A;9P;p1cNI zNG#z3KKQe!o40fYptT-9&x2&4jAx&TnL_6T6J35C?yZhK%qnoz1u zdmDw?9|u5c$KD1Z)jsurQX1*PTBY~)8dksG9!KV#KRNJnRMY?T3Eccd9XmV#`Zs`1 zKmx+KDnL7Wq*!fk0A8RSH~>5ebe1ta*c}0K!$9H@ItOKjS8c+o68ju|U zOa~y~6hG+fBnbGNXKg%m$Z!@@H9NI|3Q%$iuQ)0I)@}f`5T;Ye>&WBe)o0al)u=*L iC3$GS#r9+PZ^S=URwa2q4r*!u0000 + + View Options + ... From 9d76c32cf5ba2141e54b8ffb0a466b91d4b60d3f Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 27 Jul 2012 11:45:58 +0100 Subject: [PATCH 072/543] GCS-Comment out the updated statements on vehicleconfig.cpp TODO check if this brings other problems. REVERT commit if it does --- .../src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp index 1a00946ee..f503dfba4 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp @@ -105,7 +105,7 @@ void VehicleConfig::SetConfigData(GUIConfigDataUnion configData) { systemSettingsData.GUIConfigData[i] = configData.UAVObject[i]; systemSettings->setData(systemSettingsData); - systemSettings->updated(); + //systemSettings->updated(); //emit ConfigurationChanged(); } @@ -170,7 +170,8 @@ void VehicleConfig::setMixerType(UAVDataObject* mixer, int channel, MixerTypeEle if (mixerType >= 0 && mixerType < mixerTypeDescriptions.count()) { field->setValue(mixerTypeDescriptions[mixerType]); - mixer->updated(); + // mixer->updated(); + qDebug()<<"updateMixer"; } } } @@ -218,7 +219,7 @@ void VehicleConfig::setMixerVectorValue(UAVDataObject* mixer, int channel, Mixer if (field) { field->setDouble(value, elementName); - mixer->updated(); + //mixer->updated(); } } } From ddb144ebb585b12194e97e8e24b7e741f1b9279e Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 27 Jul 2012 11:55:01 +0100 Subject: [PATCH 073/543] GCS-Made rate Kd roll and pitch link when checkbox is checked. --- .../src/plugins/config/configstabilizationwidget.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index bc277a2c3..5469403ae 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -126,6 +126,14 @@ void ConfigStabilizationWidget::processLinkedWidgets(QWidget * widget) { m_stabilization->RateRollILimit_2->setValue(m_stabilization->RatePitchILimit->value()); } + else if(widget== m_stabilization->RollRateKd) + { + m_stabilization->PitchRateKd->setValue(m_stabilization->RollRateKd->value()); + } + else if(widget== m_stabilization->PitchRateKd) + { + m_stabilization->RollRateKd->setValue(m_stabilization->PitchRateKd->value()); + } } if(m_stabilization->checkBox_8->checkState()==Qt::Checked) { From cfd4abcf2c0300dffd660315359ee11df0d20317 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 27 Jul 2012 12:14:26 +0100 Subject: [PATCH 074/543] GCS-Added UAVO to widget framework documentation --- .../UAVObj relations Framework document.doc | Bin 0 -> 162304 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 ground/docs/UAVObj relations Framework document.doc diff --git a/ground/docs/UAVObj relations Framework document.doc b/ground/docs/UAVObj relations Framework document.doc new file mode 100644 index 0000000000000000000000000000000000000000..11732dd8a218b6e31ef8614efbdd7f16d5326b54 GIT binary patch literal 162304 zcmeFYcUV=)(l@%vIY~wkBnn89jYJ8ObC#Tg8_7X(j-mufl3@c%5JZ9`$&w^*L;N19oB&q=xB$2TcmQ|-_yDc}@B=^r1OToB2m%NJ z2m^=!hysWK+yD>1D8Bj8SkvoB3 zw{r?`;};7BSTTQG=D$MrM|<%r?fZE7sA?nYWSp(eJpuBZ8(f^<=N5wO2v;GE)87=Z{(f}&H|_r2?b9=44D!EOAlLP5 zMDEssI*hn90UN@}Ry~RI7YG2PPea~E+Hd5VN7`wmzeCzr)9zgkb<45vCeK+_ni~AyRQYsk# z)q`>wP>1nT-38#Gae+3BfJaBtAd3TV?VD$)=lZ||-p(0#1xMhiK>fKt=VL~ZVuoC> zCPP7ia4@5gK88TZ9=}HV;F}x}btQC&CV;dO1;kN-0^1!xSpfy2p@ac(Qoup?05Da; zgjj(4W(p|i=RN-Ua1$aWxpkIz?w6^7hqeUX%>wu)U*P?H0q!$^o^8O<5>Pon7S3y=&w0%Oc|5>9q)#RT%D@83zyiu3 zhL|d0gFzF6Xa*?}2?_^jfd^s=J1_4 zBl`L8hjl|*g`e-70jbbHJraL)5BXFh@mKed5e5=}bq^ENBk@=FkQN$=zq*IC+DQD> zJ)|W^;;-%@$Nj?>oS*#bKn$XEu#U{b(@x2|F_1dKMCyV4TwCbp$A2|GKRc&@WBi!{ z1w47kK2RYjNLBs0oKv`9n}@5M{ZAiA&fK8&4=NxT8d6h#D(6&^cz^5%^LHw=-zWhe zGz_G&{#ec_i3$HmiTx)^^gl?8frZrBAIdrPEb$+uMf!~&(jxmsQe*ta;aqYo9Hi6y zS2^cULHfu3@&A$o=5Jhni~1%&4=Ujp*{>X*!-*UnFjT2J;U_^KXVBP*+&N*pN z|8Ydb|B(~+zee{vliyFyx&7}I!v#1ZpM@VQ?f2HmlXHrHR?HvP`v0{n2AK`{xnTdr zicwc00REc*td_bB5uhph zw|)Mg`?J;gby@#xbN)M7krwCwMAkpsnO~Rn&z9xClND)8{!e86v(@-@S^sQ1{ySO! zSp)z6+4^S<{Ac^|j~)2W`uWEW{QGC?A7AjF*Umq_;6Ll<{}1uN&wl+^W5S<(`hOD> z{%q5KH75M|dHz*df1bzxM%JHWyI+;{XTScdvi@w({~K8uX#Z18_=nUHGQIGloX7VS zDCXfBKXMNhC?F+*d@BBZYe|r)XgfL2B1oeCZEK{B;r-DX@%OFG(agi)$LGAw(f*eA z253$EqxHt$w+==(4-Y;%=N*jxx4el#c4g!6yfrb#-?m0RMdm+R!~ecDFQ$1o;^3S& zFDBrP%zhws{>SpKDf&_Sb4mx9@%m%=Id=ot{;B+&ph0G^{#bs>!2D^S6`6PZ>w=`h z1pCi=AoqC}_V2?Lww>pd{~Uf*0~h|s0{<$( zFSPqMC^H4P*>+zNrsBoT!H2ZQKOcA?GBa=f|+~WBB8<{JMicQ9%am@1ua7XB1j&0myL}?m&D$_s|lKE8T$UcIWt30P#~bn^IN2D z=@_@s_mNi-^w8_&0d9RsbaZq#e0PMTqsbUBp6Z7TW(qn_ROCgotd<$p+&Mcv$qhPf zc-Sd4r-q)vk;4V`&|-)|74=$cvfubNdZ}eMwkXo7^lagIF707QrB%<`hdT9&Ziqp$ z423FH*WnU9Ogi7w_x(I8yHTs_5+^&_ zLo^G;q6xCvDb*2}s<`1gvtvfij*gDaE47(%&B6}bWqw5BexDLPw~X(;;qhwnpUFNs zwR>Bv>9@CbvRXZiA8xfM1IH;5qvRT$tkoEum>*Sst`&ZU1mP!TQtoSxqn-=7mr%1oF9 z2HkyP8No?R3Nx${h)n49zA~0L`1b9@j-6d4&g~0P8ru7l{jTU(gFMgAHXpI;ee*eN z6wN7hG=$a_1Pn)$_7JVx+4=3(1=Sz*u~m`AcC5+3qgU}YWS^q)g+vN2lr)KJCk-A> zYFtr-M>}}79IZ8)n3(L%2s+5LKEJNsP`iB6Fr{}BwzL?%kZq(FbnQqmo~Y%O&?1`noKN9iNSrfYx1Z0-6DDPY{1+Xp%>z`ndXn;PI>C5Hs{f+o3GsapURR zr;C2y*F7vxL__F?9h_L!;ZP1_|fxfsKBZ90*n2rt} z9E%fzmzv64P87{>e=o6y6(&P}+=um6>NZaqYNOXW<}FF034x8gYZ8rHB~j~B@0xtS zC$*lmvzYbbzZ`+wM=mx_0lHK@6iV~7l7w~)7)e|^z1!?~ncDXp73V(63r>{%cZ=eR zWZBBI>gsgh5Denw2wAkT+0&V4Ms-6uH;(*fN*a!Cr=HX=mBI&J*p1@LxB{;1k|rEV zxDQcPP#7@F+FP>(z(b&2q;|6A#ofr|-XBBFFTOvEhDtD)T%|3E(~huttdk`rbLXLu zM;x7Kr1#*~r~VnA&)Gy0$HY^Y5s&AYHQ5wGl(ZmaA#63bhjYGts9R9HHme4OYX+t( z1|_0Cmeger?m^5_LrV=_4ZV4yOmYd+J{%i8<7oyFR9}n17o*l;((N-{t5%Nu_G_m2 zHmeI|mk~10Mc*ml>cpcibjLRCyisl*E;v|gHQn0pblvCTyiE{N=v#;$n@o1kG$aHK z%jx|KyNzdphvMCfRYcUgCcWpI+!`{IW2p=CT6&%PMx0%v5O*V*>jJC9BM8M!o5yq^>@*1Uy166v96kIz*C%u&cAs4Hci7l9 z2yo3!%yG;w>&S(ov9L{1#Q247hB=CD;HsBKV?yikH29;-;iTGyD(wQ_JEBw(v?7ZR z-qNhsg`>VJhTv)ht2;Pg5z<-@+fK&UV^G{oXBE3Rk=e=fB7`dDp*AL-7!Be@BWd^o zH4LY9xwBOXQ+wh%%MQVqz%$p(8b+0Z3>vm+V@ydj!Y*=-{)TrVFZ zK7ApZmaUZM#(v*whQ+p3Ag~QCT)m;>Ky^_hH}{~kdnC`Bw(eI|o42DbG9ys#pyIB+ zuW5Yd$aYKhlK~Vm7>t4zNkl*N>bb2>r(1S%k+}>ijn2t4=YW+&W$tz!I@7>|PY}e5 zIxmNr>GxAjJ`3IIFl9-U0cS!Q8!Wh#8Y&%}72Xy}aPi`J*@w4N#y;?a!|~QQ-Lp5! zJae(w=BiD6G)^PO^OUV=Lay@{otsD?G>CxyM~?JCO?Dq&vcA8d0dYQ>hiiI5Xnqs0 z%%D2(Q{TI^?+3PlgL-CMiCdwcBpOug@}A?Ve7W$as0_2k~PpZcUhtpl~&g)a~R6by00$$I|- z`HO;qU?}aPh|0wPODJE6obiY9=g)~C1X=ImC7hfbjQ8fEN`WFkWKhSr_MoSpLlitH zvOm-Txw74k)jun#dkHq%$?W@1aa%ltF1HqCL-|oz@Y)L&I3(?~myK(}-|I)8(?LOY z(jD`6R|IvaU`p=vv3t|h!cj97QO=s)7I+j_efOFpUL>IE=Cw8A&G;0}eXFA^GifY; zCCSu!|JtJ?SaPZ~#xeVvftYbP56TP z1V?1PlcIlWeo3s{yLlQN2)%xNeqM0eQa+lj_$Ef7dhRI*FH+Xm`HB4q)Q$;hn71`^ z641l?cl0dYI%+Wx;G$zuYaQ81y^%$uF`g@w0S5W8BsWG3eSK0rKNTiX;M(h;i0}_z zT}WuW8fUe-pL9Y9+og$ zmT>F4k^NcGUuOE)Z9rI0sp-s3txY^o$NN)?9wD8GM_KZv>ZGjbfP`VM3OAn%2YXfF z?~|d{uZf)ruiZ_QfX!;V_RX>ZCsnsT)!=t>$olY8K}u;V*U`pFm-38Jg#sqQ%ZcY^ zt!8J3;~T=`V4b-xblZx~b#W&vplC6OV^q9-bk!i#jK>Tt`cN7a(RlI0;$!wxoeLD# z-rTsl86X_>dD~;}qgQ`W-@(3unm9aN*q!x~e@_lm*oV-)Zyy_p}QPji&w$~ zxm*zN2NiED`h%}gT`w1jmgjpVl#iU4P4?iLNb;z=dtE$%Bs`iIX4_h_oH9JLO={O7 zdz`6w?Siu;-Y2bD+wm&4O>dSqN+m&BEM26;sJh~^gU7@Z`O^ulG)&4K=z zlf9x^+iIik?>>#G`>(y^C1paozUAzcnw|7zM$;~G_7=Mqxxm|bAvF8<+c@^`Cvd9g z!X*@c%*K4h+K}+)EG&9|jS93Qx5LfEmIsYynE|u$0TkaKZqsit58eBqpXk%>z8IdX zafh{Fx53QRt(Pa)J_7r}rI(9|E^w(!X zatPMo%*n?Y9DQTK!;nw807eDvw$I($4;}dJt}_-P%+`y)Yq8d|#)1ZNlmCXNlInH^&Ft zn?|zCVl~?hpL3*FF{3ti=yR+?mx2x#SkoS?q1g>(;b75B(NIBXy7EKrc6_4~i^ikJ z`4BbZ8m4}GFe75%wK}FQh^wBWqC)3yrJly`1oCYfq+w;~hTq(zo`iReKZ{Wts$RDE>Asb*Qn#|e=Cr90 z=W)Q;hRJou_u=smGcq#9o}0zj#8hmmuZGj(Tvyh!EK<{NO|DiIFRta_h*+X}#n8w#h>7>fv*~BWHS_4az#Nv)OK|nS;}4 zXA{H;M!`p3LxKgX4t>Y0<}a(Im+F;Tlm@9c7wFHZRv{Wf+7PlKGUk?emDT5_%``*~ z;mv5x5OwyI=k%De+rPuRhj$tpGalQTvo{_P zG^*Fagn3U2^&0V)t|R<cj79rKMy`ZzGaU&vHp$&P@uPcfp z!I*-Ck!Z1QboV8-H^aNJ9G~6o2gSZvTX^8_x$#rW$krWi@z6s zPXr}}#PJ+aipt_X>!+gk`}{PBHuDYv|2dIQHL&oW$3jZz8A7&~-x+M;x*(1RXO3h2 zA7s0^e-xw$T(~IOYT>K0PUYh6lIMH${hPk)K4tek|9QrCj%09R}Tv-DX24$_GsQs!H=$ zHnq@($F$y%>lx1t$`EeJ-ekbg1rAu>vi>AJP$&Huzkos!-t_bvF)!% zyZg>CmyNvP@l&l=x@ zkiN})WweOs5^MdPcO1SOy8iJ(`5B5R&rvIET>eiccrP32?1RZRblcKy>>KO2lap+Gz#qd>qY zEjKw6#uf)L7py|*3Aw0C+@!x0eC~wHIxmvl`BFzPqv6Us<--CPlXBx3cW1iE{MM6v zXP+WMat4eY@_V$0rn`jExLAj%gTsZ>M=stuZg9+;Xvnd7k+*Z|TfsZ) zLyE4L3_<5|7zB0qRC=N_DS0nBq;}Q$L1GvNw)q8V!5 z61ZUW-aqLJ5-Lw}Uyj*SWsDtfPL#3=8xamL9gmK3&%!%SH0!>p(7VfZUojHi`8oMb z9%M+CtO(jC!iW(&Q)B4yNK|WzVYU|^r7^5y%r|Ke-Hzo0ioxi<2B*axeN}YKuxA%N zo0{C4_z!N9EyRCJduPGkLvul};4R+Up@(5o1+-jPZ%ptlRg1^F7*~zR_;Hhtc9w?& z>OLje+p`6wEsPSejZg2nmAb(NNrly3u79dEc9eZIBeE`@8|QPx?)!-@qLn6LmpAHt zG5zP8O>+=Y&8%t5m3tJ>uJ46eabD$8@+0;p&dSf9!Hx>YSy}f=l5!6mo^3}G1zB!w z94*xz2Kc&RNG=?_&Sd{=PQPe4HHachx#CT+5A2mFk zPy1!iD`{`7qLp4Ow%#tAYYGpzH4?bhqb6`Q8wVwI{ z;fTEG_39o8cSH`_@om>NLml>&xtiME^w`_en>no2HHBmJZU^woM(pd*4%u4?T+J~) z+Si)?aumNUGU!{T;%_K=5TN&5=0+LSdZs~{=Y;Zy0pBcX8O3U@745shYR?Bk^qB%b_h-D(GDyW>Q{ zk5?J_-Ful!)fyhZXjMpq&P%p*aBi+C(^Y3^$oCL>#1M=TcsWv)c&z3t)+AA|57Jd% z8%)%?7SYE?oO`*HuA_kpq@}0tH~SxK0hwM@S645Ng6IN4pq+u+hWF;GfoInMCmmMY z%Q~V!9-d1}K38SZ)onlet(V0=dv%3>wM*U2T7>+4mp9>^SzS7z!_5H;bLz9y8t&9& zj=DZ)pH0)TEN8y)xoNAE5%!dO>Q4w2PGn{%)SjN4-28N9C(7of@)GU6vxo2E=8RP` zpmyI^Cof)i5c1w&FwN1}T9$z;?vUwRhlw=C)z?Nkd~2@G$Ql^ruPCO`u;qhvdd5MU z@6Gm9P+xSnxsU6L&9lT|ciKQQ(RX@kdZ0br@&yN1bP(f`rDq}~Z)3pvgUoj$1~*7j z7FV85dU%F>3@W`jqoT}b^IA*#>%)&#UUZic%rBp6Pw3l(6*iwdY-;Au^Zc@7D}4Lo zjztYAMY{01zIYE}nV;<~VP;Dl-Iq+ecMY&mE859V-eDsGnd}B9R%dFln#kUa9NuxU8{Y0&Ve}*tUQ0)n()1 zD0YVWhrNEI`rDXnLb?5oC4HEKLnc^C6#_%F*Q{-=6f+1Xzr1p-*%Kev55IK~nI(sy zb!9_UEn_YRNRvxc5LqI34<|O0zJLEZD3^<)daUka zMt1KG+gM-0*T>q!%cHs9rbpM_JYC*vjx|~`dSfAEY39^C5ZPNKwU=P^jqd2yGgE%6 zZWV`x9(6dEB1Zixf*#0!(=ca5-66X#R>2a=rk*YCyBglyeC_oY{y?-d?bS@tFsC&u zbFRxl9i7v)egd!-9k-U08NZuJx|!OEbgwzAcZ~y5To6vD>zmC4jX9+9pJyz0a_Xm- z$2%e;liyX&N+`Uc!(3QDnKMjbzOWQ-~k@1yim%3N@)e>sO{LX(Zrn6jiDm{ zl&y%bl5BLPab5#NP&NjV)UHuS$^yseV;rZEp2RD%aFVjQq@3Dt^5D}H0vZd4d+YkW z1AM~s{(JB7RBFRkb=j!JZDU!L{0CWv*gq^PJ`qMs_WwS4+fmf3fs4jAK8-HYj!A0t zjXHz=WWoR~ee@et8mG5EytbCb$Ux3fMpHy%{L*5twtU>BI>GMH-FfvECYy3Bm{ZQ} z)LcPq%zKS(nrj-g67$?8V@%^dJNqv;1AOD1=g*X~HD7A>NvH>XpDc20oHERlz~|eb z_ER^;Qq8(t?XN9&Is0l^^E#6zd(Rclpf4LF@87^BX&y;KC7xczhc5Naxg?B}Z$}F; zWpy#x7@BVxIUF<5zB^iy8k<+?w@ey#B}Am%gEq^Fds2B5x{@I#jz4u>&G2JUT9_E+ z9WNnb(P5xLWC{7;COGnrRPt(VP1jo&GC1|Vo2CHS$l38XROkmIiP)Q^$Btbh z#80!xuIPl|q7J^_Z1#&c(TRPxI`i!Y6E&Uv0rf1FXs;v)+peTJ&}aMg*}fu+oeCgz~FTGy0iT3gP|g4 z2Agg%B!pF1`~vK$OUTH>2Go(@!ss6%eFHfN`-`qDv%6gIqSa)?c&Z)(lia?_a{f-> z1|s~tNhuKPS0ZD56U#fuoegX#6bqTk@dRg;$|?lN9Oq4V!`bN(z3-RHbPZ+(3r%dZ zZ5eut(#H~pZ|@gvaIoa=4!*U^=|eWf$7M#zAYqa-c4^1>ob6>geabJMWoOcf`|{M~ zj3tPS9HxKc)~JuD5(el5PK;rRMNl+AAUO4q9y(>2F!r+JVQ@U-HPb15PMMn=%0RXQ zvU`-!&}-nO(no3`q_V?#5i*gx#bWI6=aMmSsU6B&F$&&| zx-NBY>0A}OsN!3ErY^x1FymTWegi|w16R3d>}5O!7G!3w6}7wQ+tDYksgB<5x&m!R zGlp&n|ApN|X2kxrt{!nM>0yzNPp&a@r zsn|!7-7^e%8xl!Wp?}1fZ$GVBs=5pE;!h=&q^vGdU4Dkw&A#h2$8nY&Adf%}*e zn#iwBeC;YxG2BYag|Qg#u_O!U!#fC_stxFMEqDgZ=})nMx7po3 zUfH=Qds<0(jp8X+0Im)JY$CCiB9efnV7!>ZQ%MPpruyP_Ga7jt)vp*luPnuPO^Umo z`KXbK7o|U*KZ4shsP8tmryoXKH-!1z)S@B3qK+UVbf8p1hdJydV?yK!t|nd5eP`oqApQW2#@SJTIgEk{lF&0a%FNma-0 z?!0Gq#gNT&#Ibhy2|k@p=?q;XqNqNY3zl4 zJx5Wm_+tsUps7w*Mq7;=@OvgNKrn5ud1<|4J|MrzC6_OmA=$y+K|yZDTv*h>Kl$}j z`qEV|$qrUVvnc;D5!%WrM((6|*)S2uu$i8G5>H!t_TLY{h{LoU8RZ zA}aJCZC;sv7nRlkngSUm3z55SifYU@r=BiUQATuh(R=91 zs7GoRUFEFFjw>Z`Wy}C=&t#bM>aP7%Mm>7+COJFLxn;$z8Rq$kVBsZz0G!B7YZC1*g8U8SZ&rm7-1 zB;o8jd>rcF9D~!`|9y+u^s5_LO|!Pk5a8R2Suyf`J}L>Y%l$^FfDPT72|AM|y772a z^!s}U&dKLBHCwBcu0}k~HK&X8`B(aHO^5eO;2&T*XRm2d10Dzs1{_2T72kX)9=FhX z)ArW)D5lQ&(4DB@XoIj=#s}=7JS3r!y0YGVel5ko-j_(8?~BhxUfc@nwh9#bqLJr5 z3%N=z7iyl#k|nz^pI!J+Ck8lJH%?+67`n~ZuV1%9yYVo3AG-2?Zp#p;9h{@0Pn2ak zGJAD>bCB$Nf}IlI#a_38`aQW@1YDQ27;rHx(PLH8UEp&Ma=3z|F5_KYb@sPBBjTD8 zC%YYPm8n3Lh)>ZgpC}|xp-QIx;41?LEubLCZ>_MD@!e?03X2%F8F49n#n{J4%4-|9 zTW2?UrJaVF)Jfa`^Zw|=eqUD=DpUe45-kQpK&RSHM{sWhJFF{a(51qKRJQXD?E^V_ zXgO8&TN6~(_Rn#I3>c{73ZyXR^`6ygU-I7T5?9gW!i|mfnjM{$JnL1Y@+duy?aQAfQ-r)_hGGL9(~7!4#g`Ilv$~w1P|0 zxRP(~l2;wwmxL-zra%Ytmgq2fG$z(xd8>R9i$e}qCk2%qBi1pv)758ky}RY9$Y8y07v6{@A7%ZQ!0K- zY*lS8N8WvD;MRK&GG2N$HNyndcSVv=3ZQdU5CUb~)U3qS4wg(R=8}V#RP0K3jOet% z-q&hRzrOp1jN6zGRaNNYmtr?PhK#7B)JELs-CW6}w6||Ho|5spNVH^W-5Gfi^OVom z*2rUuwuxV_`mxqUzey+C3^!lHsvEHn$q#qN2xy!iToy6&uS26D7@^O0m$7-O7IF3fSt7L!%Lspevg| znbf;e)_Yy3D6eJc_1g%6gcp)Y&**iv`JZ;tm@6R2#vM@!LRdX9w5&(o-tP2jgznBk z)7N5NTZm4Ij1KYQW8oG$ce%?68&~kFrrt9kpizaNzVx-96tq@F>-k7MU14I8H-mp^ zy!S;4g42(o-SHqUn_kPi?u1NQeRa;2@*4WSWo}i(9koxRaLN0U?%h!OiR1F;VR#+m zmu@mU$YaLRDN6a^;TDEE2u7jeB0Lroo3z^iu)J`I`*nt&|m#S-t6^=<98hD0e&;$h+P(k zD#;1fTCRf8aP7zry!N~fp7?Sf_0SZLR$<(%QW zi4LcS4AAw@Ox;h>!U^{`{hu)6zOUU42_!PcL;J+Zx4eX&{~HNeaGauxbh>M}`(c<% z_Z{#F|Qt?J)@+yJv{-EU62o>LB*X(ET!xCQhhiVwd zQVTY?S*#40XB^Rz+6W(A$%S{M!rsh?Xi~QN0^AGaIuhip7;j2~C1C!P!OpfKlKj`L z{P{oRcSig3H&-$bT8^OSHNkxjYU&mpyZQu%o9bOU($z5IWwbIM1 zN)6Fy?G=NG(SedvpU@zWy}^}QDWUk&g)s9L}-wF zO*6F6hWG5G!eZx{;4^01r`AXBiPo})-X-S<2|xN&VYxe2DPUl#a?Snior^;g!UB`+ zflhkHGYTzmyZ0|_KE!3K<~oRb)E{+U9yU4YmuPA9w(4IRM9)a(x%4%s1y%0$ZMN3# za61C8lE?4_gvLzjCaSQvH%o!y4VR8(rt6wHBrm-MbvhXB?-y-+Ic@sZ<6Eq@Q^PvOM4GDVMI7kicA8S5F$%w2$8)}v zOVGHF?eu2^Ew9@tDI-_e)HqZsSLrZG8k_127hO2mBh`-+Sf9&Q-}PJhNHi2mK3Z?l zoXQ=2t{7;d$pVRZq>6z9Oe?UK*Kb;ibj)ju z+S*K9MN>VJy$_O%$#sT=1#cSFlv9HyD%ab>i)IemgNqIckJk^JpM4S>0pFrMkWAX@ zlKwcV$Dj*$wR{m$o@7^D!KU_oP=P{~H4KIqw2+9URkgP$5-%8 zdp7YC&+qAbgmmIBpI5uDPX~PaMu$#w;-kW%T`t)tNg9;=_{C?Y@$B|`L83@}%eILG z=a|PwFeMPG>=uJJw9dOBy?gj0&e{1H^*ZW4?BMC3hV|L!Yd9;0SpN0~2T$u&>Us1W z8IWDF{1K2L3dERR#upZ+DyJNUrS2Z7gT0aQ`%1SGQAhNlDUTJ(tS%!uIe2t)3^DLG zV@l`29xp}gBUJQ^x8>+x^~-?1N3xEmV;KW=N@@ly=@bog)Zpw7MrE>Nj8UY0+H@z( zoJnCXK>sr0VI{AsG}_umt?#R&NSjnGeq38CtU@q`sJ)cpAM}42F~a}BQtBzohtbz6 z9V{viYN>Hc^9TTfO$FNv+9nyC>VERpX2jD8lP3)K)Uw# zZ${Z|*9a%kGxspAK4Top#e%-E>|+dmTsarNrL~U%tHFzyDgZ8;kn*$}MsG2DL{|A5B^kDutBsrmiO0+&7PQ z$dtg)S%Gn9>b$(l*+?!+_g%LQ5mbHuN_44?w*|M$_7k3fWv|wwY(f~~``SlNx%f+O z-n~oPR^g?LREPEUnfGTVg{m8@y0hilxLr?I?m~_I7NCzI_E_VoTaArgey6JUbNv&a zd4_{8Nf)7(bG@9r5a_FQ4fw)Je45RjDi!G-t}VIHRa*M$dwWWGVYW3|=zXrK*wA<6 zQP?rtqAilyU}p};QrERxV6JUp*2)xfMNyW6A4@?NaQ3_w$>nZ7W2Ivgqt zSk62N)NROH%1^m~=&NOgWdG%wa!iK&@!)9EPiua!qO~nojv<{@SHEPf^HmZx$sP&&(#cE^;qcvjY zkV$SMq=`OZ#4hQw;h;YvSQnD9YBI zI{pEyB7FBT1|MFQ&PO9yz*E;uBRaU<)O}Ff)Iclviu^tL$ykX-SFyj%6%8_2%YGNn zG!SeggjKWi(c&=)Oo>rcz|ai?aQNsoLx4a?{ZfYV216- za}0ye?^IYx@iSPIO;^?e`D3iP!t7(5Z3lZ=K7H&K5u8P*3$-kJg?eY`gNFsi6nyUE zlGR(<(8h+tmerhscCG`KH>*Wl3F;Bc>vJAQB*g)n40*Jp-P)1%Fm&2{b~H0+kj}$)Ta9;LFIxjt2}i~h9v1X87+IfgV|Cpqgt`! zjSle7BMqM(86j=sLQ09Yd~MBOw1?sqQo{*xLuHoQoJCHt zXhs*~a-Q8&{RsiCTV^hc9MW+1FJ$5D4s9nm3FiIAAPg1!=rIbH3fl_BETy4Pz3!*( zzP-~%&OKl#ZdGP?ClD{Xv!yC+y@NDYeJlLY3Dc3L!Pt1q71q?$iz%#(Pa`zxp6FTT zrIy&U?u$38nZU ztoWk1hqZBE?{W%@;*Ljq!S>ctLG=Ch-LB!#sfC4moPOq3z!lrDWV4x6F8=2;mmA2{ zWV-QalCF;3{1mGcVBQ)Mw~ziMSk6slKy%_F9!(8iO&sf1W&5r^la0!-jmm+D*Ya{6 z{sZGjI_1~UGwywE@QRJX$IMMgjFTOmJTMG=5E<}Xsef9)B+F*q|1N)6mvz$iE_c9z zXm@o$85UIhdTn@h@nE_?MJ(?Je^kN5cE!t4I9v4H19d%k~5gGx_gx-D3ja! ztq(L|XYWZZl%GWo#xy5yn{Q|5{> z!}?yuya;<9t>*NC$Y!vt>P$>pO@fK=Sp3MoNPK(2&{2uQ$NFYj+ovvUnxl97=BAgv zh1HqN5VttrIPg=@%Vs}$2MU=!90 z^8!rl@TDaMNonrU(Cod798NciBy97L4PIq1Av#6TaG+H!Q{`g~2HcAVc{3v9@@)^R zvy57+bgibOR6Zi2?hB@B*vS{g zTbW}N^TdN0B~-G#-2ljwa8<<|?S#wRp)9 zRtQ2l^XEGhqCS39^ADTuYJqJD6pWaTkMa+u{umXp@a9lu1`C6XhHU@Z>s|&NXrW`` z+>1mK3Z0;P(ytJ_as&^w<3(<@fPE;MVzmE>c;H&2*EV9lS_oBO8NRE2?z^JbRUbrY zA4$$@!d9E~4DV2<^pbkEPu#2ZOds`q+gltEhE25ZyJmOEcAo0!Bl7=%TH%aik#hR8~1b=h+1QA58c zURU1gT0PY%%?XXGB5u3<1v7VFdpTN|I9=5VfsNUVo=|$TWq|!aef@Gt&h1Y}x+*u~ zWl$Do^VS#z&m)qrhR|DO<9i=IIF1yvgh}jD@dy*?so)PM+K%B`#jY@Y*Fc@a6^?Iy z;Xo^AbmKv!?kf#@(!qWKknE|+B2z#GZ_VXz9*iuy5j3IWgyemZTnKl5;uMTGWrrKn zP;UkOP7a-+iY0>0YGGWuNkXi}@C=tqRko;!BKEs(QKux6tnT3M)vf^4)sjQa?~41>G7I{|__1a}ER_TqWp@7wQp&biKY?SGqpv*^{`tJkWkuIjt) z5{WSrix5#6{)$NImCpe19z`OYEHxJ7{Jyl~CKAu({`v9ce+Y-dALhB$OaJ9&ooKo@ z`87)JJZ=^WI8IDZ^sI6-!vjMaHTjIfoJwh-_wEQf}I3pFhEkdHUO~qz2?( z=?V0NmpZpyLO^S`^CTI~jE_$@k(-}jVcNwD^4E4xTQMX({RrL#~&%H)9twxVvDxh{vv@q7Akkp&3v z6u|eY7j%q~Fd>(omX6o$$%`Ds|p zEGn>-e+*Ius-NG{e(FikiSx<*JXMtPM){p}UD}7K*JC-^on1*)kZ<^AeEfQo)n=}C zZ{mlKx(pAF41TO@Ue;?rsqN3MiMyiz`by z#&2l#R3Mnnul*%n`dx6YD07Zwm2)sT1smOeczgadWdQPc6yE$rZwin+t!;S?72)i94O>koZi~t749UzV^wkj3$9FubC z;+aV}bM_JcUi?b6?!=I6%`1uSDSQ7?jP*`IeC-s!X4f4{2j4f8rD=8O66rQA$zLdm zOJpdRK{7X7U9Ba&Ij%2}W}j6l5BpIxx*Rl-Z?I5?gLhRQ%~mb4ZysO#%ZMZq(F{Pk zU=CA-0BYeMd3AcrPU7^x#r0cTwm>cP3RB*neZ>2M3)m|DBgr*-d*t`-X5 zGY4)VqA~&-togd?I3%!HdVGE})1d@5$E{e;ztCRZ)jX4`Z?VUkCp&T2Nk6Op-JymjS7vY|H2YE(619+$nYLp#w zd|FW+C|s>0pHfpcPXP=9NYdi+VkIB+{g56M{>8x{#IW_|@gM*BXZV7LPzpur|3VH1 zabVU@p4<%?{X^-HPlNUisPX`CFuVb-Bmd_k02~Z2fouQImj7QI3{k+XQvYx;(1ACb zfKL98IT++q|C@s$7TjHbd8N5`>r~N_;&_^v&{bS)?77uNsz9)b7Jzk<_7&^hmKb3# z@mo}@Y}Y7|Sg0R}ieRz#X%fC7AvJvgJ)f?)Pz52CA%dh zEi;FU%`R7IwbQy|jm}O^7n5qOZp*cBIJ;!igQfT;v&l0~{)4QX#h{k5KdahcJUOcC*#q%$a$@6n;?D&^aRH}W? z%Ljh94PTwT2jCdk>&N{`ls75A^SAqi%IkP6N6(4tz{g-} z-c$d?zgAoEB<@75)%QfaDr|>9vHCkizf6L)ckTS8ZWb08hYvcV^c`yRB!0Byd;0G- zxZUnz3twdINs9fdb=Ju|L#nbz-b?lA>TO$D#=sNs+(%t zGZ*JKdYYT?LPL$F-s-yJ;0=2THNSsaTE>)7)ylBFSm#RCm|B&3b73J?4cI5p=O>W) zNbY@m!XAv*d=ua44Lt#8?5+k==mKf-HP-VTV<3B$Qn9MAOGahuoHh|fq!g60V-}3( zZ5&@N_a}qZ!(Z`ljZ0FX7uDD<;|_i`nbx3)Pl0!4zI~pGL{sp7Opi z2mir-VqY801%Q3@fwCieSd}GQl>rgJr`MLyA^1L-$iNCNbVM{#L*f%3ET0IRQrDp* zwAf7r3~tN4dRPNKog}56lE#o=Cshs+csP0?y`r3)=**7TB$R zm9co9Jnd|~*nB~r=CRRj87ZVSbun``LL#(rzd-TMQRfMi81~1t%UBC%NJ#P%!0Dl) ze|voba4WRzR*W~ZES4SgFFOgjA7=KB*m$o^2r4Xp-u&~xX)+KC1Tz(c{sgF#2SINo zvMniLfsLkB@qQ?rvmeDrJg7yNI=AVn4GY>d>r)D?_ZYOY$21tT^4fs3Yh*L+II_j+ z-`p7FcdNc`pSbQ0;*)<2FE_4UaBnZM?%jL^a({8vziVk2m<7`PXeJn!IUrFg#0PbW z!Edz1X=8@@6gAQZp{m4~ourn{-6S<3>Tlkr|9zVRjn_S|JgD>@JI`mo61ap9L((kF zZFcwgJ<1AOR_nD6TW=QrI#eE0vojU5R`LB#4S{~wktpgb5&2lP7HqGo8-wWETqx#^ zrG|-5^Xq*%;QXkV@Ocu4aP(nddUo5|Yn|cnraggg!lll-cMk8xqQ_By(17MLciid^BWfN4ncS<%F3Rz z=-y^m2Du?@FB&aNFhwD5Q$q7xJt^!QG-3!AE7FW?O>$tiaa|M5~Mk}3)LZxc*D5S2)Tl=M+G zByIy5SEI^od^TVG_yXZmtVn49(DH{7 zN#2*`Iv(|@eiHkqk;HtwRwjPjuhpn(39kpzFJqP|kyTS21{m~=c5-6mNrXIj@`i_# zIG_FzgL|+b$0_8Y)RYk|Zpe0-tPLt=GR!&bH#dhEGy?=Or7btRUyho45sbGR7Fs%= z$HlWHB9a8$*qXZM=3p6NR&X(GB?~kLR(v9)vTKVhjWv+%EJ{;TTGQ&tN(A@Pbr+#R zv2JrxHi!^xScRBqvLmie1(XFy4QUW&AP28zGFU&TU6xo#Ep4Ntv(fT3tQ(};l1Emc z51qwBQ4@oID8)E<#O#!S^oK7XrPl~+Px!oTD;aJEjz$X9l>>t?e*$10FuCs^4 z;J&kkzl)`PHHaS5B6Nx08QeXi>tt9fk{((a}#m zT?#8@j!05$WxAJ2N)@V`71c5qRl6jS7cTs@xD6H_J2-4P>@c6qYgdb1rd&lMw0k1Y z8(&TdQ(A_^p}ZRpYrd;0DjJB)j9@>pQ3F2Kd{yPxQF~s*+dth3&C|6FM@5c@iE0t? zyr>cjgy))iqnCu^MIL-Ib0gHWF#DIJaV&)-e2#hO1|um|3<+(QEyo>CHR^VQ_DV1G zmUpiRZQDp)6+m)&e-ycIiE7?AyyDYlGCb#G~CnK*ERo=DxZ(^zF zoDirF>2{OoNa4x!CsIAg%;$*6fLF-0s6TsQBVz}gO1Tc2>&u`aP_%ZKe71w^s#&T0 zF@Dj1M?sZC#s>YX$uY)e07Hh|Rhc_VD{6>AWNByycniTuYcFJWvp-uoyRQ}jt@C6M zN(gH=HPT?)fiQe?MtAM)!NB`bMw85kAFUL%LXDuNb>oXk7{ro4!P>jU)%P=-vXc82 z_vzSN|9S?Bq-W1&$J^L=K}Req67P(aiR6yU(c9}pB^FpEi;3P=_~Uu_9v7493V29Afn5CEu24cxbEmTAb)-fw#5sc>ik)Z= zR88>mcXmw#&8UEX3MGdRE;71EQS)Dt!Dy&PA?OJR1Ike|#k|C@fc+$Sr%UN#lg0Z_ z)7eNeze@=o;`oa65aE26l(eIQhCb#?E0=N&a8b>1>3ZKeZ4hN5f5xOQv(+;a?bHoV zI;}*AK$xI`VEqk~BG4(CC-hfn0JLqFyY_=ESCu6zdAIZ{L$d_N@%X3`qnIvM&#XYxdvDdIY_u!8`#IC+iqHD-2vPr zJz2RdE!SDV99>NRUZzrb9FGU#BtOpcxJX7GGXKOZ@ZXO+jhKHV3;F!_G#d{U`GkdM9#)sw}Lm{0yq?*M9(;jY(ii`@hQfydCRJ27kM_BLNN6_s^S2+uKvM_F}=P3M;*M5e+sqF*)E z7%00MjPo_+UU%;Q?gvQ~P@DY67=uwzyZi|k1x5RoskEq9$N8q418Q}yk1y`J^LRD* z;=0b}UyFR)^U8K+x~1M=J&!G0Eo@thcUz;M*Tb3qK8;21etNI8)YW>{;pQ6(>IdJM zAFVeQ2awXH7O%S?w(PiD`OS@y+EY!w*~^%OqNtd52*L7~BTq3>fH@;LgUVCN7df{L z&|H6KTJOQAnM^SPvy7ToXx2xC!8bxIrQ5=*#sI*NwH5iuK35EcErPx^n*MM)$P(;o zNB5?&uhiFW@wsKdDd%PMsjA~dT5ZndHxvftHeu7~UwWeSq<)p-rM6Ct|HA1TD!x85 zI-=gHsN~LbKBc>64JJIpW`%&bqXF`igMnK0X5GIMI*T_LpM)`6vI1RY@$#TL0Q~+D zw*zFU-DGiQuGXZedf#=tXwkP6c9=*LI+D5#Px)g$#H%aQbmtH`%0=D>?B5(qTkmi5 zw$hI^C=?85mdgX?tacjqN*uRdtI+7cQ%cJ7^kMD&8wDLP?;;|Gzg%(IEY!Vpb@#rQ z1MK8c1oyJ;p(Wa(o2Vmvd&Q45 zKvmz5o6;;vcpY+5qDmcZ0J@I$_KwUqqCGv&JeqHI;i-uN%RfpQb{S_rZv4$hf-!5? z;mf*LI2D$C8@!*MzGE!~_RPN0+Z5K_s;N=e{_=2Wa}>knLXDq+(^@E zl_xA_IP*M0Q^3bFK+-rqy%iP#>yC7qJN1&ewC(t)p{u^K^enMB4m0o6&$q#pVGSfsYi zmy2&N9<*))B4nsehSKl$Kaq-**p+8))VAIsVp#g#w=nBC&zg*Uj72ND{yBKE-W&Cb z8@JnvL1i_yW87l*XJH2T_7f6$POyj2*NHKO$Fm0n3b8%0%VS^dB=0Hadq$y=u9aVQ zvQY7`wY-XMC%dNukT`ll`9a~tbTY@-m4+zcDLZ+|Hgh!yubD#~S3LX_MO~z!Xcg01 z>Z!xtw`2m>6TMZ%;94AV(nx6Sk~`#Z@O3063rQZ6E5$)~#vI_rv`Hd|^Mvz{fr_6U z|B3tVI-;PSrtWxb>%CKV$3Lj>T-cz~`Gq}ztRNLhA!7?qsY8ZpzcZ%71ycU_rxV?d zny+krmE8k=Yq49o>FE*O!%0--ifdL*3fr>jPOQq?wA!bj{Un!n%M)B3D8s8C~0gZmRdo3%9B zkEpZy)=8-?Sco76G%<^M(L+CH`?t~Yl0trCvQ@5JWkaY zEUIWeQUmICepCI{S>obcJ-+#Lrd8-kC;pCiF@wKsqtVD{x!-A*$&X<&$E|>D@K$(# zRRfR<w4fSxR}^ut%5Mh`_Huk^Ziek9XVZ)s&i2UEllE1op?x(XQtwX}Dqk0WTb)}z9Bbr}C z?eZEKj`lt55WmZ@KMtLj7x3yl>17r^)S9(5P@cro;JZ7YpRw*FVWzmXM7=h&zB- zCJaTu{;6yZ_Ih+rAsGRJr=epUH@6Qsit(wQt@DaA#S*yI;A7QWh+uj%CH>>%0_k+TM4+@Dii9_(j zA=$*Cr-=ZYX`zZlssoVN=%}0d#9;lkUu5l!ogN-J9&H2_vql*bd*}E29s-XxNpd%1 zAQ2fe`|0mrA^xS959@lx{vHpgS2_+mG$P<3ZddQVTAF#$q47!36!p zSu_o`gi^cS)Y^yr?d?v&t|6>vbHPyzFhA>gGN0e(fr+IFdv65VMdoFAe7IVp%)pZB zd3=MqfXsT|&3L0*qGh7_T=#JQ@LqrQr8Se+r_>ZbJorVB6n+})Jt?S%2t~I~jD+tq z{kBrZ6e_hZQ^{UE&k^rP+TDtd%ksr~dWy^0F!y>r1zI0|$=Y{Mw8e3Pk4(L-taV~d z>9)rAo&14kXwM>4^1%(bQQ7lZ`=?C76-TcdbMYGT+6;Xf^Y9l}%lSZj zOVx=iCY%Zys4qYOGBPNBBO0_4mrJ<{-b>*mrD1b1?mD(kzj)TAfN8!uZZd?j8AaZ4 zzW$w)dbMipcYGy@`F>+KU--^EBRB?A+7!P=`0VE= zA)UWFLzao&UZ?4s>G;t2Ntc#0G8O`?fxbF>(*a_X&-gD;>ha^!Im`)=EWYOPw$73M z0$$vwK-RtVG>f-h+__ZID2hJ9Q`mrRKoK-NKuL2vrJ?io{5f;d9@JEfto?x(hlHcg z^t#XBOY*^bAbBFsWS*R8F^I5F>6ZlMYSq9iE(|Vr*lHmq6JZlT7Sm#gO)3X_N4uN* zzCcL1O&l4xAVGS#x7z=zOyXN#(3=ym5@UJ*dInE43W7YN7tGCwy(V?)0NcEMoETXq z`ZP?Z(i8{L^TO~w=UgBWCIYFLabd$0Xau@aOth9W`nKq4d!X6XF3q8U(JJc3x zEZo?Xu_s#c<1P0T3@82ryh8K8=M#=_T6}={R$I4hy}0g3yQ*~a(Xfg zNSvLx4!gAyyGJ#1OMJVGzb?aqU^}tykf>TT%4T7kXlyK41TQ2Fddpxf^SFs9KnmJ@ zBLf176vXSgGgSUA%+*b|s{xnbPn+dG61w?<@DW5(x!`g0O~=W2Gw`o@AnQgk1jP^f zMz`{?`l;?t#rAsCyArD6$^bR{6d>rcV_L<+fbWYU1{cAljfOf+i3X|8@bdepd!gyj zSb?#uqIu$|Ynh9eOqwXhWm2I4iDY<CV-$ykZ?znUkw5%dXUxJEYlB;_%*AM{GRw?ICEz~=%XM=+pIQDy) zrb`TUtJdNL)5pp4nriT}qj~1Oy_tyj8y4KW)Z!`R3>}OQsoCU2DJ*M15ra6v3z}(>m$3vx1^!AnQKb>gPz33u68$wJ7BD&qBYU z5%t0r-d?4zlQn*l0EW3lq};sPtm*{A<(!g2zBtv_wJ*Hd zmzqHW`I$+tvg*4DnO0L$n7qQ6X~Hj54v97?(;t(p_SH6ZsT(cXoVYaXfrKiSbPoy- zYd{8KK|fKAhF1^o;P&R^SDmnzLK(Tdxn{{XE7{R*jEbr-b8NQP)y_TGIO-Yd$^{$Z zLhm6>iIiTj9h=CVz#aN$CEtXh`>hsItm`s0GH5xcx!~Gi4&iUF_*jjw@rJ71GUBY3 zc?Uyu;ZhJ=1w}laxC(1G-1m$n#Ue`Pn|`!e;PgS81ls4^k{J>tozGiGLw@~!o4lTu z(Zwi>wDcLVA8dDqCVsAG@nj_+2V-iJC6CT*>6h`hSi8;h=O(b1pE>`QO%iUrdFzN9 zykS~V20NL{6PPH_Uj-4xL6c}`l9ltc`aZsm(9V{m8VO_ZGqf@aIuuSaO)$+f550R{ z>I5a7AK1y+f&Org9^zP){)*7bKD^0@!+DN{5wwm-e19pUakZK#>XE&F)Ag2)L++DG zi(KDpQ__#NWwD)+pX$jpee_OwtsK~b9o@ft(Gqh=0OyGs{R!y-MQct zW-|65QTll(+n_P*orittczJgb1OvvPSI$OnCeI$SW~`bjS#2af&sA-t%pi^)CJ%W| zW*BaOSurkS*K47*v+7Jm*qH1SwiwS8X`SoZtgQV}!?|NRbk{hbaD!`6cIWj;wcO6J zs+64X#8}wb!0~*bS#F6=LVl&lxDP&CgjlhWjK`;&vg@)E)(^!k~nS&vz`*DN_nK{u2e zW8^Ekl!^Y#5es{n3@9eC@giCXZH@_}!$rByB@xsr8ys7K8E`a9(rZ2|n|s_;*q;Y9 z%NduU@V}@J<8g~?F<2NMH+WeG6{znl686lOwmVhwF;g>y0i5l{SI5uR&lY|Sl{Ipo zm7dnn<4;Kx$4O2}Ri+vB3YlA3)RbH^$9ZgO-cQ1;nKEofI#^r+ z6d-=s+c{tt8ikq!4KH-HhFM!@TkMx%KcPP59wxDH{i-IL6D@mwo9SXZZOJZML8cj4 zoJMgka-D2Mk;cnm^mB5i(pcN{cX5R27qL#6CS=&b;*8mpMdhpm$Cv#|o;@0)2tp%0 zYZAVIxb6*tak_CpsT0V+BV6#<+mHv0v7eaF^J#Ms+gF(m`saPY`BL4r*sOIccyzEWo`%2uaM zO$noc`L0dK!2H`ao^aqlSN1i7`t)yyz%&Q<$HWzwFKz;oZJjpy#zh5#Bk)iMBu?UN zr4nDghnJ5MZ>AUeF&HzCb>3xn1{c#DT=Y3zk}k12{u)b6{?n>#WHn5`Ib)RWacbWw z1c#d8trKalWL9#C5T3~_M(O~R?7tjPh5bM~P*EUb*UQJk-a zV=}M2QWQ^DjNg)DMDU{IeoVEoq5AO<&>R$rn2>ZOkSxYPaEw^UvkJQ;B+=GbRk6Ju z`MTpxkU~InvOw7Vb%HC;xC(S;Q{s@Lw){PNG1xs~G`eVLtdT3E)T1-0e$|F*;H``W zdQs8&e$l7!#o=g@RjUgDM0bO03sm>7g_Z0J*G5Nj2p#h_}kGe(%NX_!lAFDTptRna{T_ttHuvGx$P+>HF0sUoq z>Hn;;B|}C8{!ZbAs;EIezMa{a#mr$;_84RRHZk01Q^^f5_8J1Ju$lzK^oWl5*&WyP zkgJ~UI>|(s3r-NdgnoM!OxW@FSmGWi&@}w@YginH4M^Z?)}&0NR=Kq$k}P+1jC8BlT_QbA1s=D}N;`^Gil(H>uFUl~EMbRSXO_UX=t;Q)AJk z9RC^h7Akwi+IN1W+YW-YXteeVi;F{`QC`2>f*!$`#eg2#m;hqtKvE!X9=JA@T0i0S z=^qA4_JM((GQsbcROo(0uVFN?P!zSexH#V`2mBqSG*p(+ZJ-Xte6yCz>v{!xs-Y?0 zShjKu$+)z>77&T;`Ik3<28fn|yi{8?qsds$iR-75Cwao~o;ws8?N4X%ZZNSq(hB}T z;`IT%1ek7U)dvl-%UCHOCIo)~U$AB9?_J++7)lsm7-(r0)0zq#=&nA2XvKbPK2nla zel3h{m^)Q+PWM-fTFB<`_$ELrUa)m=Q;mI66FqoU*aL<~)(eT?jeGyDo(48uVEGT5sl?5%XbPqSxa}X!S;d&&! zHOy7Zh=~hB`H`PQC<}RK>kA-S(rrzmzJC#)6_1;y=imDtG%2NY*@r=|Mi1-}LDZ%e zX5B27nLp&kCP~au4qtGc3+cRQ|1`dPxXnc#ky8|{3J{Gy;gF7? zqrVFOU~0+sYj(R^yUD$Un9?Gq3eqQft2z{x?S9=4ok>Dks3f zjx47v4e93|{L0@T8b2fS=7#j(190jtGG?(8q>DZ7AMD=P@C9_65&h%tKvH;zr7Vr$ zFjB>b1kfMcgLJ$$;1Y~6-5e1Z5q_0lr&B>~>6yO5YI@1x($@4PRqx|40h}T@W(52Q zp`6Ekx&`Q$nbXQ+n~}q%yy?ppqq{(LwGNU6bEh%>z~uI^kq}V4F zsw0R2y8leRZ*5_I#6PF!szy`Xo(lb%2HU-O1MB9K4}q2sB!>-{z?`lwojzX>-SgU& z)t2Yp9gllm6+Kr^wB0FM`VBSh|2;Ie zJgw!jB&|c34CBjHb=4L5flHx`Xq*J)zcf|os_K=4gzu#p5fA%4HmRfX^ zDqyjF2rL0oBC`D*%e{Su+sUP=#@hPkZK>Amq6in<{%{x*S(eS#%Eu|fx%ZqO7Bzdl zqid5; zprHzMWvo>+PL>cYKh(QPfxtXm?I+`=OwW7EMOk6eZy@m&2wQP?g_ zR`T<(YHj9jo@yE7n@+KRv1$0GrAO+LJj9ujNo^Xf)?1g0onHM@V5#$4fywKsp?-|X zKSz&@DqG`!G*_B>hW1=aCl8qXMg`LyrJb$W5Dg-5RKY;+IleEilIHL(F6QAde#hf) ziAS2a$S@O$w;k_aW=@}Gv%8)|e_i2)GXG?cK>1q45m0VuMdioE5Ah{os6}LDf#H%A zI!_R6qIo|n({xB+=EJP7)wpT$Gbg>NU!21C%vi8VNu^0~J}RF`=C-(hyTc2Y{^o&~ zWcw$_5%H^PVw~!_!wQ0<%mwS;Fr0s#TGm>IOgK~_d)~&V0^5A(o$R1`5AoN_%>+v{ z`pR}DK>{S-NH~S)P(K%u$i8b+sd1MH#4Vj$zz@ces$wH58!x&L0lvt))Mg6qYL}}E z{-OzH26jE8Z>D_JB)<)WcQz`ll4-=BZW=!0n4g}j8Xq_h4;TKqP(z~9@5$}yI`||$ zfZXv|Hu0Kj)F6j$QS`l9-0Yi%r=}AFny*G*vPs#Bm?}CCy{=^JuNY%LK&rSctabPE z3EbbX(A!KJHr*rAx6>?cEDt)N3^7_pde8L9I^i2E51M&kM^I17F%!{Zv1rSQ%UsaK zt%%AE-o!!Gl1K$lseJUF=8kdeb(ULmocIc@{0JWr^<*XkUJwlL{LtJ=*tKpsw}_5& z^zi6LDFMRmNd?Kv+`ioZn|s`kzsN3mHqK}w_z zi~T-gHrE4e^+eqq1VKA)yByt$F`a6RszV~#b^${+f0@K@3*8?&8APwW@$&krM=cD}wwY#WXgBVb-vN@m(hEg{li| zhX_72pyUkKG5w&}liQO0jz{iQkaeh8q)|cLGNG}g@%l6$+i+!N&p6IK%*Ed1TaY>X z^F#Ga(j0Eld)lZWq}HEOxU{GW0@^g_h#Wq-7?uo(HMT|59oLDbNyqwgWbF*bb{96Z!qUF4e?kmz_=V2K5O)tZa?iPI1fgBci&Ry|oxw_?mX{LZ1f?}Lu*NaG#ghcPWI$O_j;x?E3dKd&HXw?elqisydY~vxBOxI&&Zx=Pja4q;c zpw|^7%u3GdYYjn5feMK9kXmoDVTwUR@j7D#{B=h?EkLS!E|lq>^)5bOLhoX8Gi=J=FTH~PYcUSK(S7+zXu`UU4fbtsJOO)SDVY!Xm zgb2!)$Au+gV_~hqVbSp@_!dARoWwr!+?p;(9I!p~#S4Xo`9yw&nrpVD&q;$~wUMzu z$b^Bq47K8#FceXxd}A4pk2~?y)z$S}7M*}h<@$|iS;j%W;S^p+ppp)-H`+VjnFJ_n zM&>n>xDGCpZCgxEHW9Z~lK2ORKmNs8D$g(t_r+qmLT_XHwE}3Z>gF>Ue zGU|QL-m?+Qpn_BkoQ6Am(9B1F`W#7_XVQMX_m6i;{T7MY>GgWlr~ledHE+bHkcfbC zRDJ6mw>y|o%JdEFzh;L|0w)FWK>i*;Neb{iv{2;&5P%oU$E7Jy1T1jqa9cZ#YWP-8Eiw7ezbpQDH8zV4mNO-S$~VAhCpZsb0IIbN0EUwBJIDG!V`$|X z4r=CA-Fqtca6`0y^vthbG%Z40(Qg{pFG_DEiA-i|UJRU3M3AXPDws(5W-%hcLODto z2oIn5sl0wxR;?!kR8YDO@)ozSwe9uqmy?t0&YJ>|APPLI0l*TR`8NAFN(FyC7sr=| zx347P(jpgPns*mb_Mq#sFp7XSaz#Q!RFurSm7IX0HW-rw2AGMrd0Qk&K> z3w>_3<-}RQ3ee2BLcW>7uvAxTtX?BhjK67ZrMz%Io^7XeDqYG=(($4T=e0>MxgD!&}>c%BqfNb7LDBrpkwr z@6_$lR`B09bW>uW1Q2yR6cgT=Mu4T#aa)=kZ%xy_(bfPa$*m$KQ%Q<2d8*%ET>e3x zJ8lS7bDw@Pff6>3Nrk?q2#hoE*UEDZ+VOc}O)W)!L4)7~LM7VDZH5s8>0oOAQdlnr zZz?4_5CPHCD@s(c`F4)Xdqs`127FeL3CLt3e1*NOcuB$OAgv$0CHgC0qS%NuHuXaw zL`3{CbR*|mkrmfY@7WXQbQIT6n!Mw{=t<%;k=m{$gp*RN4&tdY zgR+Q{uR}Ii_`r@GkBH`LwL>?T;=4!Gs$yCd+s8~EQ~bJNN-`g^N0=&o1B!_(q~E1d zP@YiUXy;xJp!~5!KM)6D>!S}OLQ$_PCJJLvObSFO&BXU+{*@^A_+x6h^>GhsX8Zj$ z0syZT0iK0i1~u$iF-8Rtgw0Y*A|mcHiW?EcMsOW1>|J0fEf(gd$;7``Lasm%1!ftV z6pCOri9I|Itx)BPi~(R|nT%73&(Q&xZ&aFVF8&m_v!*Cr`TNUQxVpXD@vd8Ubj{o^ z{=LdGs~0Uo-1LMMAL6HB=9>bBAw4gatkV61%%TQ3v)E8oeeqrUbE2Sb3!+$pZB=9t zMynhnrjYMY9z$9!svDbsngi#qCXy%26@6xbF9dxI-xNWDtksxcCYAn-4%J&~#f3x0 zkWLay#+s=N?cvz4Foug8te_k<{qfzZp|J%yd8Hl^uI~-R^0V{LEe@5zIbtvU><*6yK3;+M!?B|9aKaPe zAA9v@I;XZZ$%ba3_U;Q*xbH_PFaCPO<)2C`W_XxQmA+)N`u0<`gK8a>*nq0$&E!DH z+sr2U=fisI0?{2GO-)-dzc7$?P?KCv6q65TI+Zd<@g$j?H%ttS7%~fNPrLqLppG8V zkxZMdSuq88c|J>pLeZA#!SqzHozFgqH@8$ai+$c3n|5|-)y_{>`6Qe~{0=%Km$HKgX+VJ>#r@mD?5Bn(O(4N9KfG}p>3BbOqOh*;P7 zK_C69CDA13r&a$Xhv%pLk@dU0blEh0G|?(*=tnj@7_=(7Cse@HPvCuj;7Le@>>0tv zw-}mR>Zp&Vv%E)>i3VS?J21^nuo|#j`_Je+1m7d72Zo*1KUN<7LWB(zFCyo^mj#Js zh`5b2j6;jA4V(rQ>nhzg#m1uWDc?zc;x&0`(35X%*A54}g z1Y?$($DHzTzdF#)S2aJyVPHms4?vm%rLxk7O&<%Acx0)CjJ&S`y&*YJ<^qXHKxXRq z7it=S8b1;dB%E%i8@)h*tD2hUyvACAdm>_RfCNZ)GgHL4Y7GyM55C^kaMJTC-E}Q= z3a;*`nwevzgToW!=u1nv~W1 zAqCjY(KB+O@-tEoi3;s}9ClYjYH;{gU9SO1&4q2p}!%OQh3X>P<)>HLr|e8$?` z^5}L7>^R!I(GqVt)7}K2-46(I559f=?DD8){<_kn)66$}QNjwN=+)=LvMq*hm>Vzm zzij0;9O*eMUx!95MDDPB@Ts<4C@+6sMrLQmz;Qb zN#~%u!8LIq(Cj0v@9W*v{)4*K)~(-Fz9+A2iT7O8j>kchh38rvN0){vZ1(tm37$6e zdb#ePmNwVtdd+hI9TEiryc%%bL@Zr2A4sykoy`KuPke)KNta9IVr2C|8sN0=AHK1k*ow9zIpFFCm zu5GO_JaeP^6xFz6ul*A!IEIh-8I1hzXG*8B3scb8c0rO=fJ~yS9hoELZ1}_mn)LWJ zak1|FctQ1DX-SjWfoIN&R^xV@JKwt6Xyy=Z>q&5_x|k;zFL(1-K|=W4@W528xW;<< zeU(f%W{yM=1V0GcM#vL5ySs**)HOCR=w2}%{31CWZZ`o+)Nq=tZZddB6AHE5oj&@t zc$>W};JQ>WD>9X^JS@E6f|fGZ{0VPd#* z*U3-&1)9prL$WSdsZ$PFaZ7|Ae;2P{mlSn>6-w`2e~MD|2sCYMUU*c1wVnQBeLFy` zq#FGdi1UIN*WA>2x&loFtM^OKH2Z4?OrQC#+1@yQlXreHOiv8Y{;70%wWQbVWO+9t zI9z#uE@N|8QQ|LXH?F01#m)Vns~Ff_RE84X^ihpcp#8d2f~GY~*KyXKSzmb-W+<8# zD0_yG@#-%?e#QtqjD|YiSG5zc{`KUb7#x!&R6*@LMc@8&UN*G~@cKIlG7NPDv((;| zLJ;kWAFFpXq*Y#HBg$a*AJ(CphuA=Xp3AF1uv-j#EEcsrXQD)M$S?@k;Ei>#|r}T6Se~9@`9dwC@7j2(@It= zR|lA>F>dbENh<<9TiN>IfAxEQtjhkcy9j!)t20%ByW&P=z8K8tE0Vx-C+K;5X<#(l zFh$w0QW0X9!CjMC%&2*(_8*wb)z;cx^bi%yoKr#TH!To7DXo08*)gfX`~x@H;)w%E zUZujQmuwnmaLQoG$fgIYpQ^i~9BLm6XTnahWpVJ)tMcPxA8yg0TEg8LmDqTE<)V9y z*D0x|eV&k}djx6%fZA4oB;?mzX4;}kQOu_%D%?j> z8c9f&q)m@jA>V(bK#}m-BRR6AZNvZaU?>U<_^>6JZ=J?>8n{WDvC}gg6oe7vT7*JT zVb3<&qWH2r2f}5=3^xF z4KJvguv#Kf*gaO$U3sB#aEh;<; z)W2j9zEZb(M?Nob+|I_kQgxCyIbfG}j)J@JtEhr>u%PR?>>9%G0;4O)4}VJz^3HwJ zU|$rnDlyx)xvOgq9O8Wxog8$O=nW@*ff`Xe5JcQkZru~1;d}{5&Aew0G`kg|EYSRYtj~gWQIUJ zmhy$JVn&g`p`|rQ%Wo(3>>iynUno#F7AHr|a*rggE)Ig=sj+%4#{;W}f&pjtW$}>3 z)8x}e^HpI`RfRG#{vo#oK?TI}K)(xe6en!o|?peBx7s$<$CXJY<1r3l^-jyAs)Pf@3+bz>TobuvSbw{3_Mul z2f>1Qu0GYf?xeV1QGhpXX@w@ZhzCB4AV51wBQ*}K_&YWLXMA@iB{pkqq}!{VX_LW% z;MgbO;8>G9Wk%-@A~oR&MdNQ8c&hiYVYMx5pE4Xh)4H97eW2v~Pvy#AgZRDqu))Yj z7r@@!>Gq^|*{&1kz6$ioE$O)mvWso{e9H<^E^aLi(s{Wc!btm(xV^M?~RzG4=dqJJ+Yt3hJ$?uZ86Yq61 zseLJSi}Ut#-6}*uAF10WQdOcf#K|@`>VdMq z+y#UU_48W4A8b>o=2aTBeL-Xd-coX0$vlJT=YnmygeALG%E(Jh(UOz7GKDlKyPZi0 z>QxhNpO0`uL&$vt`vn>zvax4a*DJqfeO6`C0PGB-etUwEM|Z-~(vnW2vqAR;08;)t zY0>Vt^Yq11z4wD7Xbek8D@tbQ9W zNtuWBRft1Bte~1v3x~5SNabY|8;@m{S`}G;a}6+%2WJaV8d)Kk%Nn4f0*V?x%>fEv zR61^bv@z2l-KndH02u@_MAZI*5!m&snRV|ofwPs%HFTR5l?1y*Ag=qm1)0Uo&|vEEU?W!A!3p|msm^oe0Pki=Q4uHyJccyS7~g2RH~pt20UyeD@k`H*X9F^2SpVjxzfAMXsSe4IiT;Ta`?RWwxy0eM^I3D) z$lUoLpoY}A<-$EZcMSwbf7McQx4(+Dp=95T8UHY|HQN)X{xVC=6>0M#SQs0T1WA}?t%YQ}VCT$u!APvD$xG~$th?{GJ zvV~kT7LCcAR#sKACT+V+Ki5r8>ic^$lbz1+w{yj0y8fo9-#qgpDNFJQ9DAH`&Fhe} zr*o`Gcp~Qmyrw3%y$1aEDNA|h#P&z$1PL_uRF1a9pdjO*gchIjQh(^%xBgvS1vv26 z^D@NW-nKLKe~uoVd;PVM)@G@^lGicV2z+{a`{z1z z;V1@3XzlOpK`=9}5*tmk{TY+_I_{TnyZqs8_+ATRO$}dM^Y5^^0+Y$!Gnp-G%{}+JmzUf%GIh|^ z1n+lR^K%Nvz8izKraUUi*h4N=?-jO_nn(V|nN^cy*@K%Z3%ao*x5&PEg^POq#|3!< z+f{D-gxYa^p|RbdzqY8-R(Y$D?-k0mx4k)~!ru=r_%wIhX~*>xaT@z$R+%!NklV35C>i%VunL^qfws6#xkhGHWBa}v8FKg!$`w#!#=&8fO1 zsUh?s(+dzj&;0BP>90uJ(x25)I{OHi-8|x#nhk2>Sc6A5dAzuR~i= zBN={+AoEolSX!ItfW~^8CwY(LYsnujUd)6SRU@DgNtX)h^q{8P}goOf6cO zl?E!-F)3?W8_e&ZS~s0fy=cT=Y{UDE{6hf&$riC9z8HeFK=*(=Q&nnxnJeriz~80G zuWliX2d+jyEQ%zF%p(j2b~+mA^s0a0rjN8AFhb|_=Gc`5?KON@5|IofZ5MSqRuL{( z&k_4w7Y9{0MJBgnS~tZzk6j0lS-%MC3wF3qh$DUZy*06LyJ_0~`#JIkQXSTf;Z2%u zv7)@1wd{^Tz+lSP@f2Ie@3PLIdY$6rKnNCHzz15kBqY{017E;nFYA<=lL5N2ajhgoB22wt*pBd!iRUG6O+{AXF+?}+4qwFZU@ zh|~;Suc?_Mq#8Ix46@$8uOx?IT>}HQ)P8(Qdml6_;QU*P-8-u1vzlWRk$l^~dsyKa zB3nb&bwUn`+7j1RR1{W{KbA}L$~;V}QJ<3I)N{t)#k%eVp{5;UxRp=-!N~T)op+&+ zc(rWz=HEkl#BKAjVFLH$gqkcd2Vp z^-E%se3*Ye&D+W?39#uq%TS!xV)lrV`@AW^R0xJ5+G3j_^|(Zs@7`Dj%qgP}|1&DpqX+*3aVwQX6AJCEZsVThb{NMAIoQG#AXio)=ljszdf# z3>wVt`oq1B)}M`%V8qqC%jhcq}wpMZ_RQM4p_oG~9a_2BoIIn?2L^zCOLc zCwQO9FztNo&1>RE$H5$=_8Tclvyo%ls~g($b$b&^GqFZmDxV zfQ4eFAxW*+kHys-0VGheQy++CS5sS6cYG zILe>~+S_D%9=LBYg)2V?|1njstt7Z~RGDYD$!#UqH&QLEqNz=u-k1X~WICp|XyxD- zw6?y~Zmsq1{W>1b6S^89+v`Skcyb1-8OnIn3-%)~4p~w;gnyWncZsGNAo-yavGUKPi})wkEZFRxik`7krp~LMXgy zoXuPl?$-cbD~ebs%QoCBz9Fs4JycVS&fGpBduoW$HD=SJjmI&_UlfC{Khefpd^iNq zDNo~fAIp`)TLh5kZz%{CUl`ZKQa4ZK9D*rcWdxvx1`MTSGBX|$?Y#|o8s_63&UGwp zZyCxiZd4d+EFP<5qrv#Dxc!abl@K+kRqMNMQ9_P~0i$9~vS7rYri=#yHIU+eW>1ho zv<@Q`o5ybQe~nOZGA@}t6oVLIP-<6`?4;daC>6=sfrJQte)&rg!Eq^p!Vw#3cf4ny zE{1Md3z!!S7QV`|JdxKY4{TFt!fWo@R$I*s0^K@`L?JAI~X z9dAD_eWs?3)qhY6H2pz2 zxD3J?)ubR!Tvii;(qeC?FJ|-I7#sU|kV%oku2f%Pi2_w^B1Vg+Ug}W83Of5s9w>pL z0c8iv|8J9p#qsOUiFpm5JRi%qG+chmFl?9n8whEO1!ae#Wq_5k`_6L5T<%1XLEC2s zCxJWKDS~NOOs;z20cZMF5u-&b>W_C8%Yv(^|Yi99?85J1YCL+RK|5>gE z)v&!eP1Q?tyw{RX4whS0m74VqF7@XeaY>`E>9;H?2X5>wXA_>X6<<|Z8<@W&)xofz z9ajo9tv8a64t}x6^3LfdOSZ2?k-_ywpx4JJNL4L2LD}$j^?j2YxruV7*(g7=CbyXd z-^t!;C<0ijUK_LfD5X)TZD?rR;Pe$tG8@Q4UQ!7|DPj0B%HKwogSg@^G6i{!A2{qP za&!nxTNUdjhVVP2>QRNjVh6@Z0xL1bo~VkCsVXBeD>yRM8;z1?irN3Hl&lO(hHF2qF#3huO%cD#pb1#@FEuk*vXC>u$)I>zo!+}Z zHa{ibeIIYwF~w#}+LbLf`ZLVws zW0`WJBlf2oE7^|t`k1)px4~*u-tl_7Y@>93!LVgb1QV{DSj}^cwcOP#9IiczqNoMh z9nFz3#<5pUB4$CY?YU~L|0g>^rFXlmBb!eDE0W%T@c~Kw+(H{J-$Ef^KZj76@ZO!G z4XZvoL$(yVozs5XqPWIbjQXYm%46$^0L)bKU*ASE=j(NO^T1?VFasW=bP7w0smGzg z7E|^&CkXK9>1Kbvy4$h3m-ubvKd&?q=__3ORZeYf?Pa`S>7F(Yqmfd6~BMMDW%mDHh;; zX8ED~RX%v}-{5_BynWu=yrAlcjXHU5^uNt=Zoh3@lnzBs+^MMqtuEocfSQm%H#TqW zKWM#aeo@yE`3IpzMz09ss;KcJe3<=dc}>KiG|126vvHFi*o3Il6(Qi97>rBBGQ~zo zrfJ3IyNcvaGQH94u~1Yf%gc z(1VBeWM<<@JK}m`H?r|r`L5&NZyVY%_G`Z_CJ??!duCsz4~iebQ7J*88102C5>!A% zZ0CQpY0bCs79Bd;S-w)6NED{WYK{o|%}D;nztX}v2m?1(*MfZI-9(xB??u6U^O|>t zSvF2nKl-digDe>wkwnD=SW7WWU^=z6lfP-&c`f+gDWeJhp_V?HwF_Mm+_elVeR-9k zz&{UDx8i6Rs*Rg{?}TdEl7DMw`cElr%+-;OB9zQY-*NU+*gcMO+~&9c=$#4Dzo zhErg4?+N$5q0j62f-oP%#uEC#?D4mc<`9JOi}{KkQ>lbsYeA4+r4s(%XW{Z+;YD&o zCI6S7nHd4p&cQ@+Z0VOC)=OB-8XTuNX)$FQ4D&27=FZ4VcSR&?LhyyvfRweptX+?| z^>b4F<1`ILBI&F{%LSXiaT}+qz(3l#zOzmlGQHTl zZX9?EnyyN9S!Xg}bSF};jwy!mIe*QQ{7-WP$Cda8yZ8w6TB-#XDh^3VRz?x3&Cbql zplU?tq*X*QJ8ge9&)GR&01(tF3L~6u#Xl@XI>c`f;g&ys=+qc<)ZayWiuw8ap45+Q zR|gXOA1#^by`LRrK1GR{RjtleY`Y_7;w*8Q>sZoh9r7I(s%E{E6|KBuCC-xUxbqjt z&G1~Q{*R?CH^%?FFF$YphDYP4%}yZ4j^{8)oAocQ-QhrZOV%uALVmm^AVp6q&s}k9 z{~3f6x*Hto7!~kOAMbzb|7E8CkN%&IfC2UYQ#kM6|6(sn@WPP7{(q?d_cQIE{vS7O zK;pmiv=EdH2mMF?uM_e9|Ed4igm~}&{N(?O{vQ%DqAJyY^#260MXM0a{(sj0OMCTS z{l7;qf2#QoiG*XC^`O9l$(^-V{QqN1M>NjLwF{ZQQL`f2hJA!(fD^F3=v zZ1Oyp?%=nbqGGSw%7beDDlPE2_k@#~py`)An{nvDMDRkM=ze@^-@$icg{$l90uj%u z^78V}pFbBD&pJ9g*x3nCsLU&R%7zz}lyo&TFo=puFfvMWatXgb3j^!>WQP!JV17+o zfckP0#iW>7ZTMPlcn%+YHzsf`rFx56_hnqO2)Rzp$OoIrpOZNhBlakvVC3L?9cGEu z)Ef3Z9F2rmIc!MI(%3k(Ppy2Gd~A%Z!%!v%{wtH|h;5$_kEfq^2sRMKH5U0(&d5uP?ePCOq<0(g;fUF_O+g`- zT{5G!jZH>s>d8-;eB6E4@iLo16P4*v35;8R8nXc6o*9 zhnMp_byD7I*rcQd3H_H|J{pRNqff#b9XPnBdn`vI7pOSp{2QKLZ}u&^NPl|@j(HII z7j-JA9}u#qvZtQ*tQ?IUKcM}QC!9a+bk{YGYo{{t+DgmhmuLqwl~pr8av*xc?nhlN zR=C@2G{akSu`bq=PIuX-y4-QZ7}!Hx9*Ml9FxO~vL9zm3Y&MBb>3^p5rt)2hyN zbR8Mtb1;WS@9ir{#HIwZPb{ao7pg@>L@YDxeMQMB4YHsl7b5>ex2+(Ov5?0e^4p4g z&px09EA@r%#k6#3f}1O^YpMQcH%?8KcS;6#zXVX<zY0x=3d)4ilH+>5 z?2CnTH2R?*bMz4VXS|trj960p`ua$+e;lzVh5VI~LUkrrPPj2(O!9y%(Btgt(~QvZw+=NH z5D27F%w&Z(YUUk&-uanN;LQT`kEfvdFLz$ok}g?l6+!W!aSK*tTD}h$K?FSwkFlxN zYxF6!k*#6vu5H^8>zq+qP{jv1q$g6?MDAU2`$+d{R$Vk<4IQU|mGd;d4NQr5*b+OVi z3E0DvlocCM9dG<%C4h`?&GZr z^`ve>g(tNa0Y-~OIUi}XEp|?dQ`+BjG2$+tV4+KYBziS=SlsnJ?uYJjUZ(3oQ zzJnEasp}W%%))|AQ;Fb$H(!)rLoj$G0!^dBAySvH{-+NB?~LoEMaB(t3muwN zf09S<-iWOHqHQh1@f5be3^2UuDf?dmz1?&7R9r>1;M97&w(soxmT&C zdKv<+`RYGMEBw4{UN!WZ@uI0h9LXvh$R=fl65sYhoafc=j#Pr&scucq@o#h>Q6@YU z;5+1o$)Gur2Y~kgf;Hq|J9BU;lHJnIGis$mZ#?m2U!>9V5H`A zr3gg7i89Ony>fi3L)9d#>2+8;d@y+dQ~rV33iu5m2Fmuup{8|`bYpPq5*H(X{1Zwp zgF27}6GrYsuF&Pj83NX9PNQ!yt5s?#W)r1rX=^h&tL{fAzay*kkBoG4`;D6K{26(M z7wg}FKChVI5_Z5-Jcs!KTEWUc&|7;iK$a*h@%#1xE-qYiEG&Jqw`OID!O}T^BZ)sm z7W^>O@G+h0dF6ZQV_hw+R75CTdb&k+wng@~oA65JAwvr5o6fKSX&;|(yCoE=c6}tg z`xE<3Pp=#YbBhf3GDH_`T}BeX*b+xC)UecW)bQ1a)JWARd;^?X>)w{Ss8MFOcuw4* zrt}n+mNm{#S-qGKu(`FhwYh15kP`OZL|E%g z9)e!>kEApd5Mg2RWe6W1VRmpM(l?X}EEenv92UHaB)eWTz65Zl3g8%z?V~Ju@5u>z z;fKEGy}iAP`;n26#Kc4x3`QyFZ1g4Y5y2(btv9*6y1Lqo{&(&}@__o+CjKnIpr9a@ zu!;&67PJN_9UT%66qdrSE~*527CaJJm}0Pn`BgA81=?%@c+eK;jz??pEfcncTp`c> zdY|}-Mh}2UR46VkzB5@Mf#57QS`PO-AQakqZZ@Y1r4iJ~*RC7Af%*SDiFa|xCu9F~ zh}4iwgB~xl_-vpdH_*7KC;($gX{n?o5edmAJwZWo9ByU+;1Y>(AXm2NEQ`Py-so&` zmjYzyt+Mjql~-1lQ7I7fBk>Iyh`{z*yG~@@==*#`3A`5fCLR8p1lwXGYkoZG%t2C_ z>*zFWwV(e{Yk2DEy*I%fmm9#0MvCFgH9GBthS@w;JekE=E0#lSW(o+!7rB{S^}q(c*+ zo%)uyXoSFVlEL28gkinJIqs{7g9PT)(WwcSLQFUwoJ9QLM4Ai}A=G?+d1-wG>>7*1 zHKT%N!EoVvQ=<5a5k4`m*&|+SjsT`DD?g%x#-@b9#zR+}p--2jC=$vDn%<00a5D&X=mQ`Q?lw3!X%~B3Kv3 z;de(x*)KW@-Es*gfLlP{_Bgr3}1pNt?0m>pLxrIa({c(jSLTaYS zFp0>dVg8nCfrOGK^nsvr3gGi9>hr4abFS~R2r-UfeJr~$RG&WS1+ zdj;tji%G5e0F1dJlJ%>4Ia9SlK0{3_y<{G#%*a+vPpB>D5KlW!vibBYQf)z}Lez~v z58RPm_u5Ifr_K;*7`w97&-PR^h;J;`qfj!U0lw@Sa(4ok3+erH0@d_3bMS@>zix={ z{X)O`g>UuCIM0K~07fTA@2j&dj@(!RH5^4yHXUpuB5FeBsH2h} zC$lpGP6DSQqv?%Ds4ETM0Iq555t`w->39#e`DqC zD2-WD=v(A4fT@S?V!(O^b}3 zjww?5vUxdIeJ#7rR-qb6xiYORHRc^eA4v+AD4GZZoJvVBhMWv}O`q&NxwaGLPtLWKnJ4Jz%VE<2-S#HZ6W19xjugvZ2loQyOCo4Nm9_+ip;+m z`Nn$w)@Fg$(99Y17R+fYrCumIVeY0WbOSFDNQRvT3s=>=?Cg43)|J<%h!KZ@PCjKC zOmt=>YK&>FTLqVva%BhyET~4jOVuC`!KK;bE3jMGmu@X|(jshw{ zP7R$=d#9PGD&3%Jd=kG5k&sR-$S?fqvaK4EP`ChP`lLq5venGcK z?z5^OVj&?BHX8zpL%)ibrBrXNs^48OgBstkVo?tyfc!!S`nGok;#kx?JT4HiN(gmI z3`@LMl69TZNbg8mb}9hlXgyXSf5~EJ|}XH({`60`a8Zc{)TO*_s0sxM9rb+ITGh zRf{6AwK&=hlajUgq8Y-#CXXux z6wS@r;y(>&T=G78#eZz?TloBA;WOfOdJ@a_>YVr1r}fS!>#=(oz0L#u)9SA`Q_hk( zR+OR>$ht6{FYHWT*jXZp7k3YgBb9D^D4mVw*FRN#ey<&{Wv}@b=O`>u(pUm?2 z$V%Bw=8Nr`h4jcFd?J&d3q8W`|BM%}`#(-(Y1(jF6vZm(`ghgc8J}ZZoMK;H;(jH- zf}J0{|Jj$z7Y-g&fA@_8+KcuMC<1~P>$$p~RBD#L@ZF^qLL0aL>@*4(G@C@5gFs%; z{vjIEY5T)sC`(~Rr3PnYVetK;QWrVn!i8$TtYm+J^>^6xB~xyog$mX*Ll=^8E#M}+7Q*UV(PY{rNm5mDFJ-JkgdLL#`3bdh zW?#yO;>N(!Xw!OgHLTwb?eIxDNXa_*%Q_h8J2>hqdDtmwDPZZ*Qc-kOkQZD@`atRF zL3*H63=dt+)}O2tAy#Lx67|3^vWr2T5e9$2F#d1QCKo2*gRCn_77&9GkJqfhJ3i{? z$3iNAc!MK1yCmR2{sh7(pQtyVuQwmD&H$B6m!)D0~J?pgxKzdfH@w(jlC z>wd2U)VovEyNlGj3;f)%XQk+x6!0zJL;T|BI$esdyz4tvG2G$O8-+PFFJ%4lGwAxx z@0Z8plPBPtCo9YnPwa3aUVbfJekop$+V!2i`}=~m)yCTrE7$@a8&ZtL`JahMT$&!& zUr4@rCZCUR$Ke$f=;l`5`GqDYUomuLR8?_3*qJKKnu%396!xgrrs5zVl9zY^G8Qd> zJ{mnAbhN?(z#UHE=J^JssS!L<@WVD(9;E0B7=aTj_a-7DH?-UPnP8+9YO^{e#Ny9= zK*p&j0qRl#YHL_wac&{WE;1WBp@+^7Pi+AYb_(ArO20If0NB`Kz5S7{Ag&&Fg>$;p zs>EhQl}|5i>I8`Bk*+G|9wW{YYJNy+#z@&OqOGww4Q|#&SM5dK3%&$NXuns<$b~n{ ztEyFiL;xqqASqS|m^I40@b3r;e*^c4(kjm4ciL7hB;GR)l$5dq+ zM$n5U&W+y$9>J}q6Ea1A0k7be!HJnb)={*jr$xr1QB#DQ`K!sX2LB|mM3O@cHW7j< zWCk`7^eT~Lz!-8WxM3}LecK+$I!_I*R0O{AhwsbNQ%$kTMsyNFs!XA}Wu5Fw(uvp= zdt8!&(g|&%lz1Ov-i*rOfTGD7;rMG%@aQJi*n;%^H8B}79#X|$u4H)Y&Y!N~cjU<_ z?300-vW2hjlR4ViCo8r6z#7Hwz7_XB4j0pSVT%p z2f6%RZjIvN-P$-yJ2>H!Mqs$SBANXMuqReEA=ec%6b5CpNNyo!ke5*7s`}8$6wl^U z)KhaK3Yk^Zdqy$^059|yoq(-@F|<2y!GTz0I-yN?~V3kk4hpfT)+;Foeou z)EH7}qbYK;`U#M6k)7KaxmtE3ZcJ{Gu)866ELt@VPzExxa!rk9k-G^CA&5Y}t1B{R zVQBP1+KjW9Qs1rg%SLG|T-bfX$#0h3L>NP`Ot`*qnkMrsmyt!UWN1zY!^I=Hnsok@ zr0peEJ0vRW#i-yeEE&Kf>BB1NDXi{^0!an11DQg;M=qlc3PHPoecSzi66rKq7(-n# zlL$CC>E$rq#YRK1QO3}8*74(CV&T6#k<=EY2VoIC1p)xJ@Tnmmn`waKm#f9V$Hqt0m^;gR%7niz zuiM(AHy0xh4qLvYQYHj6)IE(Hb<+DCBplTiPEoIw3wNppcodxN27aA>Bz|+9K_jf@ zyA2&p0(~`o(JS_EWdf+;cU}d9eJ6 zz2(eWq)ZK4RvS3PM?JhHR=vKd{cpl-as6d>)nhmZGPq1pCk;novL9cjp19Qi>^|9d zF*(1jrB1(nGI!do_S+QiNuo?Lw*ID0=AKseI;|4Arcq*-qoxeIg1beV zV!6tGrFwt)w7SA_7f^K&{MK4JqpHzxZLZkvX#Q0w>YYcKc)&P7Z59)(0oLz*qQbxX z0mMMPOm=U?-Zel)R|Y>WCl&Hs67m}sGF^?y1LE~-$cK0u9F?W*XCWXCVlqZZ+$7zn9A#SBmxbH{9R7IUm64|vSx{&ap&{}Z1lRb*$bE_pLa{Yh zKt3!p_TDD^Vsws%Z;*(LNVN2?iM+4EDw+fuIQE=niqQGp01J2mC@g3fNFBZ*UD@LJ z9g9ORMCTwMiQ@odXhblOJ?lO?kZ2wo$qgRZ@CitUq(~9@t-Jl5#EpZemP}vYnk}udCNmq4Dp?53D$UH3A!zu&I8QmRE>%RVNfZVVNkSsDsRyfhVR*zt4HaW2DPKy<2C)FNT#Wai%9LjFNf z=)ot5X8?(kqEaZ}=XE6s3;vU{Qqv%!hnc5sVwXE{4#o)3sVFZSMN<`pJCTad{18%F zrP@5lLS{_s%hJvtya5hADh{$L4yAoYhzLNiw5PG5XTayCLg}@|Ql1YEabmmQWwHRf z<;vV9x4U?1~XDIs3N{Q0m?zy5c2iL zEMf$XN`fJvxN)q34?>bm5=TOoN9VaPn4XGV9OZ`i0;{E&p(wikpX?PP6 zULoGq=kVngG5zd(u%}mcm8kwwTE%W${UNlS#sj&(JOFA!cp*w3suaDC^?rWGf@r6x znsbnibC8v5h>-mkCI)R{FE2gl3l(y~G<&6RR8lZiATuUAW3M6{&o>V_aX0Km*q%!+|1DJ+>0(cd1QIDJV-P= z9A3nj6&$gtVAa!wSGQ{qEs`W%Rv=0t2Oz3JyT{bo9Naya`7l`OC0QiPXbav;=-@kIWa;ihU za;{u%FSR&MPwqC1xpq!Ferj>OF2DUOF|qbo$;*N4wV4S18F=p$hCMY*lwU;1JXxr! zuBeFlTJ~lzYyo(#0iADX0Ol-En1f#Mxu%GC)soF&#=fxRM$dCgPXykf6rZVuX9gh^ z%bQ&+r38oLl97M=?7H5!!4=_*L$vGWuuL@m_^$TS!2R`sC6x$XyIAd9qP|Xs_EMtZ ze4_4}9^8>lgZ#I>Wpr7GmIK>t)>!d1Iy?OrSNhr^E!imzYg=_P17cKn&pdto^*ZO> zIet&Oc(KkuCKY?xBuLT@64ppaNvQkZLg`9Yp>Azb_XnI`80rS%;%_t9@9akcF2 z3~JH1hW@|)*!nfMbdzW2Yk7LPdFuLWGxv-!042T=#8vXbBI2%r?{5+LEqmf?BF$cQImani?bMGdCErybWr z{_&XlR76Pt^c9&7#@|IZl)3AdOV7kRN}zpz{3CNFeU|`SXdA<3AID)I#euv}hsDyM zu1Bh^M>?UVg*ymv3(>>cj5%PX*d$jZqaakIAXLgB7|)(6Chcz4s4|d5th{&(Q~kU! z{HX#PvXP9U4-guNpJS@{^i!)2(GQ#`yqaKN3+xeD3fnGyB>puHr%n_Y`01wmIm7GF zb;>;mBk+lRnOCO0R0}p%0xk3Sh*6t16K|jaOcAg{N;Uyyqy&Yc_4^!6y5g_AKyT8?I3fkRY)#P;#MWgFvos~zLrH(u!vvQBTUjZL%z zf{O|pIwk8IIdlY=OuX@ZT{W#Vv)WjH&roGKe&2g-S^8bC(xnaw%p~hn-BhPCKP5Q| zH(XeiPHpW)-rWF$=i0D|?z-u6D0Svu>Di!-VUJjHhYH_0C>td9VTl_A@OhUqPwrS7 z1^6j)S(2v4<%w9fr`tUbz4f$2<5Zb`tLB1>mqzUQS24yO=rq{Wh;%QSI(RUTQJ)dx z-7UWzDkF+cPL;rmyZ5a%qgR_N{CCqQlvp<<5N-)2acKAp`E@qR2uOGBloDpJgOVvL zt9FTT4woMfLu+Au7w|EABnlfmma=d~+@~*@N7>QY!$Ca)7gSkGDLRaJkEgqYum1y8 z6~F6wkXOF8Z|6DOd%h!ce^x!s2ED2mbEgmOluZweL|#Ja&wJqC%p+gR1DPbtT&DtW zL2*ZGC2J7HdP;(GSK1fN!Z1M1z zAP{A>3T*fTvbfwLTdL%~nNlSlOKdqN zTE~<51?EC&?mIA0-j*0F&|7-CHagm?a<@|Zm7CYhIC>Es^yv!kujKFG$!X0Sgdh*hJ_7*Y&2F!yBp7<{ZM`T=q=8o*lx5dRwy;ASLlQU#lQ^37y`C5lvQdv z9L@-MNm~;(!_FjMn!TuSpkz7A;Yyb57NhBPh6rQ7Y+!52*nxrhMTo4CKYRQ(4$^;x z<{bAz3KtGMbljio<&nJz%pv%o;N;LMO=eL25-tY@I7BS*dw{OuiL987%$;JEKMYD~ zakIvCGeFE~Lv7Dh#Gui%GX%prIr7LMVKsJY*`Gd|vB*23P`XRnizJ#T>*V*o0?~#d zaxpUKsfcu0aJ)dpR^Nhon3N1jn!dUL33Rzwu zYW?>jO=pfCj3H>QRK|+XXF3A8o@^6$>f#x0wIwOk6CxDSRyCXHs8q-mZ&72I4jFPu zq=Px35Jaf`70U`RlU7(jQopko>m8q@@XZI8iHtDsmR8pKF5M14fGd*FFm^7%sYu?A&rnKmXi zUD7mDkfJ<`Q^-AfcLVP{Lmc?-TXir#w;q70f*A5EG&sZn4eti-oalr%4$DLd16NqX zAi-uNscOwoNa*oH!76X>LRATphdIk&Rk1(MABWw)yuMlVdip5M>y5~uuuyM` zyUy!N`{I5d*#o_d8wzOpbdwVv^7wgh(s2l8+UUjF3NF&Ye4{Iek=~CWpG2|pK7LML zP6}R3L#GDx?vVM#NusW_yU@s?&IwJS^MuNpa=|=Qcl_@jD*Xn|=!+DkQk0szVsQFx z7b&}ic}%mEZ=iW>x;Ck{&5E8&)}5WNW znOKv@%NMT=hK~{{Gauv>(GTIP7%q%mNJiI8ToQZaoL1k$HFd z@SZ=S{u#zvn3LHO`~X-^hLKvGb26fBUR$t!XsbRT-mw|aKd-_Z@bo%dqa$i%mT{?? z$&qp$Pj3;<&gAM_Yz~-YcHF@dx9dEc<(m5Yca*sEPmH`!-xac54tvW)<#uyHX@L1< zUdVfxndd$!1P~0K>0z*%5+Uo*Wm>ua`f59Xm4Br~0=HU0{(Lem`KdKarj};eV(EER zfSQj~$}3hFH=ICxWPsjrDPY8R-Qys|c+s5&_I6L*sGwbv$&f~AGiy$BE~9c!C9-@( z3N`9?e^w|?8Dg!UrC0N(HHn4+IY3gVbK;QiMM5YTlyF1*5lFmmOw+-m8)apAR2ViH zId_~qM#}>0-g}v$%IQX&TWokR44h}$IV7mkKN9voy|NFXg1x!Hiec!LZUhd-nd*YOsn zhq`{B@vvoz`pt*V`#T}6dwx{rz06z}v&A2=B<|zrZ6DQ=2|qf^pM=8a1tU4nGJOwU zMt7cDy`M}0x8p&$Kwg6oYq&mIBa89BSQMP1-A#>} zMqU4w@$z*wG_vSWtl3KG@kE845yTSs9|~4;ErQL2&vvsTVIx9rR;D2nEdF?*`Nj%* z1M7%>XUGw1^QD7XCm&B^o1HQA#z@v8pH8H9M1qc$+Fz~aJKMBXhP~Suzj}FohL}5R zn}(@gWs2@zEb(3PKE;V7Z)&6R)i)HM@HQT7)3fFPzJryGmS|Y^N?xtth!?hvpQEcJ`2%7xE+GOc^p27VmE^?zJJ-6tRBL(OIvy7EA@5$lg4r8CcC<9#=tqk zXER|K=^(<{M#`Xvb+IS;m_W69bgje#yIJexNbv@VjAB_oy)Z<-83f7-!n`|N{CNt) z<`fq(e=TM2B1!vW#D(gBHAmn{p|2mIFW%!N2?2%7$QXrQ;h6D6T?LatN&bQ?s35)^ z-ZAovut9L(2@OiQY8ZzvkK=SKeymBH!G*=Q&85>=8|LmOsWHmQQZ64(hf#N7rF?e1 zJEOjw$?WM<9(&*6dS6l{KH+P!%Brl1s%_#j~U4r?jO(uRK=dI?+6j=S)fUtm79^7dPtd+%A{*OqMh}% zs)j(|2C~mEvSFbdUI&-b)hf+kzxX;Yz&IbV?Y=$!TGrUK@TKrTPt#W!W0Bjr1+J2A z2*{oakC&`MGc1WEjA7!cn)V%V1fUb1l-PF;3B7yeDb}U>&hzzj4}O#a!{M-;cb+gI zxS3v7eO5UR_E#b8M8_^Cr0}$zk>HtF{V4t7p_NF*64LXtvCx@Cmz40sX9!p57p1fY zjK;*1yQULk2zgN2!?t@eA{yxRm&>y6{waxlKc$xU zSc0mR+XS+NVr^e%1@19p`btQjpfu)nHtT>wNYFp3X}-t=-zt36HWXAJ(%pIIHl!ZZV7E{uj zYw!$Sizk|Il|d2OP&8Wly_-DFQ)=@5x9%2uJ+n?Qaotdc-*9>_(I+Z>S00XIf7|aJ z8#V5IS;(~dJE45RShV`2QcYYD1V%^-VZV)VCVL3--5EoA+38465|Gbe)zh~NEOo;~ zH-jX77U=S9xQexy6I%FN@J~FINJ&-~{IczI7p!zv&|84AnI(;$av1(?uOfzy%{2EG zOb!Q%8uVCCL*!!`{n_VOO&zW=y>1qV%c9(C65<+tbfS8n zR__URYX=k7;p6*WfA~dr28PZTqb6UI(|w;C;$Vr`pCFU(hL4zuk4M#6)g&eL28mtv zk~3rBr$mUR<$%XMCffnPe-KSNhkpOa26}QDxW`-n>TIcs%|qSJv8zq1jo+4m7tanYx8xU>ZjHD^$)Cl#TnCpndzGBPEYfXZCe+QD#wvwAu z6}2tg>^*$n8x*p2qgw&C5O|^US$I&dD1Hrl%^a!rJP~^@GQzZnSf6wW&N+m)5pibh z)M>F4elD!16vbbjXAI&@>GtmkAwz4Fu_WMSAsU6Vd9*q9WFQ42>!E^9@bLxl89@Q= z?R5$P_?#8h^MgoGmZI;<9+$C!OE=BpdAqBNS`W_A!Ed6H`^r-R{PB`gHxSTSH`fZ$ zv|gQ^GHnk>KQIj3#+X`3IX36kurj;z8$B?!YEy8`igMsUiJY8;oIEwvF7CH0d7lt~ z-0VR{lS_`xw${1G(3cN70_%*%oLbj%8XG2tqDt-1{kdvPloa`^Q)0_N5#(NU^ewi@ zrhd;+gmhZEfB|zYJ`BJcPo6p|ou57-flqpt>iBdjb@73@dqWbn#mi1LI|ezC5D&^^ z1^BxvWr3RIsjKP0VFicj_l^M4`^Y``7mWci| zEi25SZF%9=z&(Qkt3=5(T}NTt4Gpc+uN9l))1@Yj)^Id3Oq0gajN^D2_K98hUN=7$#u^=!D*H@L{+t2m(M9*Oe+;b zR7;{H8zX2?HzEo6SHmm&`r6$@ViP7ki>15qe*wvnNc*__O*NpPW~D?fQy_D9S^ z$A*uQ$SKz+?yR(brfZ`Z>JU4bXm?%aZ8{yNf(q&?9z0};1KWWvAY#LHy2Yk0|M4^4 zJ9ea?bb>DJmMpm0Y|Mk|&(X*2yl?TxB`$hdUFOzf!|a5wYLJp8*3|GeK8o^OgQxX_ z!}p>W;e2wayZ?*5_wc9s5C8uUhhrUk9`hh8BMu>}V{anaa_CsuBMEV2XCx$hCs|pU z#WCU-nb~9|vy7-v`96DpKELnn`$zn`b(fBtbDpo)>p8CH^}Mdf^@v>J*HN4+2&DFL zuf30=yo1G?%c(;UQcw{@trJ`_3QHpQ6oa5M9^YOL{i^%ktG<|?6Kb#=hTPOqD?UKl)Awk=$U=9{HrCkxCW1+0%SmryF|pw!hP`Q!fD* zAjh|)C4yj^Vs${+-a?_sg~sDrHxuxbzZ#NeNpu>#OG`p3(J)=Hbi+{90>KPM?J1WC z_7qi$M2H^jBWgB7XP_`Mr7L>P^q%@Fg@{yD^>_?I=2Cv_d(p1c{`rP@I?onFkTo@n|I-{__N}r&tl5v2mE3rV0eH_h9`b z;rwUDsqF`qMxi^S8Hsir{(+vu%kSzi`+aK<@%>IA*CnnW_-;f{KaRv(Uya^@9MBgo zUhsBx&{qC@D9QQkT%~HUvnh0We&XS-Uf}DreXA?W4ZPt$W8RL+V)qwQ>fF`)@{Q|h zADVwzj}Dpr-sjGOqWguXM}$&ysrBdS67Xw+-HA*YzOY3@8N~d z-a2i2IDfJn#_W4ZoS*Syw>d%e{*-%H9XawPt2>HbU1D-01>$F@`l9HD2?y=Vl+1(p zYBvne(yPYESKT*wmH#R^cJ_HOq%%+EFJ`j@aC|7?4rAv<_C;jUIh64OmqcM_3Ji~t0<~l`#MlsP&uNbwzQCTIiSyM;$kW_zcau1DvTjt z=kkoqGdDdEM0$o>w%*nFC^%oXo?Bs${gPR+*OAaFCgVqR;klc7b81Q#PB8kOI5Ppg z5UjrtEZwaJyF6J~-})u@5-zli1Plq}8nQ?@8n&gEZo6dIhcIjGiKpdCTD?;X zKNtuXiGQkkl{b=H4`z}McT8tpGh=1U%!y0sx~B!ZW*GKB>nR*h1}7E;CPX(0SZjvx zY&wpxt8x=EGihd@C~jG-U6$yQFU&6gqFcapn~q;@nsDUL@g}iP81$hJgA1b*6|BQA@cl8fG@@tk#5eF`by3F<5u_l zFVi~=(*-vivnkbJ*L)bKEEhG@3izBkb$+4agcG$WdYyXrpt39YiOF;X+0L}h)YU%L z@R0pi#?4F`QM-(eCsM0uPlF&kk086ypgU@=jGF#x55B4-b*g={ z_*LZj`lIZ%N9^G5fVYpQhpT5mIj@2lD_6x6iYXxtR*k5&otD_U5BaleTCj2QT+!7| z$W+y{!{<&^BMfp++0fs1MXw)a?j4p4>Qb}P(rOqF8_V1zCe+x#JU$*)-Ub2PeSdb< zSo?)s@ZIQ6(qZ4Ij*9U*UnwAn>+WV{7#Pj_vR?LeMGe}-zSIMMBhvBS9g*=;l8s;R z8T!}3(cBT{s57{o?D(yM;|*<>@POaiKf_T>S;<<0(9~!L*KQpdRA6F~ZU!z#1kVze0 z&iYQHJ|GrJFn!%279u78eq85{!3|!T>w;;w$dS_!E*pGCVByf;-tNsGt+Y;$Y`Lho z7zNSS`4X(g5O$xqZ#%{W#_TQ&QDJXHLXIBv!X24=wKa$dl#YmAvx0;*&b9QlXtvUu_;~OYp4;qclk9*e3aOKrV?6dohZ!By#HhxiFfplRh zNoZHD5R0bF`q?7hYLUc=j!}CfYnWCy+z*}bCsBTQGM%ax)f>s*UY3&GMMaE3uf7=M zd1!pIl1>OIlTy?TiS{{`5SPS@>40Rx>=Kzr;zB6h$0yU#D41v5EZIq~3R($qM;l)D?e+7{za#tK9v)g;C;GDZXR`I@Z;wy! zu7{t_-2ZTKV)y#@m*=nl{;;6>))}%2y?-Tmg?r^{44DX_Z|Su%x^^p~opqA>(0I@4 z7i8qmRAuKMfk9O_VMc+HP}^ubnwdX$Pu*j_j8vR?Q81=7MZG7BZH=$O-Y^RYjW}3U zYs;8u-BB|qa4S||`BQ{m^KT!d3aOFh!uxy}-yNOKZ~P6Pr~BL2)tl#nx^l)UD46~V zRhdYkJAi~H+TMxGdibaqHF#HgXt!Q;M~dcJXIs&Yxj0|K`@47Qv0TZ${#Qt^jLB{$oMn-b@V65rHLal1?~U{2K)9G)H!n!Ut`b)>jM z3uC?$MgGCl`(rSaBIU5h7DIXi^Wze1IG5L}`PO*+Gs!%dDz&O+5@IJG zP1{I}gi!8zh`x5~&#mfKs>+OFmNv%xrC6h4@4jD9c9PK+jdtR@k?mzJM=O#YTag&~ z%n*w8geh1iCb8=O2)2?{l-F%De2J{s#))|fMZzCjuY7IIx7v?}pg00pw229&>h$s476nPS@)K^_ z=|B*!s<4&B%I!BQStoM!9I7yKj$a#B&o>#3>HS&eRPPGlg5u7}Rrn}LYU-?w&_;Ro z=1Et|Gz=$g_08=JP3`ne?6l3UX+Fq9Z$zqS25{shyZ)TKyP`!|cu6_gwDOPXvoJTk z3mIm*6eGIKn!YiTM8lGvNfJ0uK1+T{0--Wqto%LXi=`w{MnUBzXCiF0PDlog$^DcF zh%?^}I#dcSi>B$$Gx6|w$*5?C%=jA`dyzSbv=ABEUkSnlNg10IWCMBjreOD5NLi=X zHam$y9<*#E?51{jgLrN1-ae-*Q5&vn+6zODQzX#%*g1L($`2HhFGtJZ771S}cBvlN zH1XvcYfBk1Mqhg?KC@E|6Iox1)FTF7d%*ATq(uLfM?UZ7b_$_t51YRQ-8{OzGVnr_a((wBnADtUb)C|<6z0{(Ev>w>L40qR?0@ePFSMotpHXYV6?=mxN4 z>Qc%T%*T&g0+gMN1j_5x?SxbgG|i?1QMCxm!y#l|di&d^%HkRu%bW-UTLtoawCMdx zYcCP;a@nN{uZ~xRj)rno^IELuy&;whIp_f-x55(Igg=64cXM`6q+(kD zb3Wj0>;U&5?sb1uB6(g`rl`L}{Y1O1f=W4#q0()U&EQ5vU4O3_p2UA_DeOTMoDSZS zTlFrp(7CTGEA#U2eCS&G=K2&XjTUs$I#+G^u{c!%GE$30{f9Q$O${1K&hHU< z>*U8he3Y4+$-_lSFXTw|B!4+$c)1J`^&kmdtmUUz1zBrK%&FZ2@j@zcjoMzys*ZzOHzk^~RFhQ3BjF}}1guC@of}(z zOjvo9@nxef8EvRvPyyz*!vKk=ka-CR4t8=lxg?fnHuY#(tZ*JacFV0U1vZvtY@RDH z^dS|duEMo7UzdzD?Y7K_P)4Nlgav5I7v#83q@M>-akC=ET93FQ3>@c;2oQbtlzSG| z{Au+i>kNGBsp@Oe(u3^vOdsZ^K3vmd%xX7_Z`HR+kg3+Rmi{6k&O76zo1sd7g) z#fsWfoPnodfIAm-@~z#i6T9v!CW}kGr!>#?8C4p$IcKyKyoK{3*}p4~eagZHk|~%7 zD`WT6jhq-+bZQHW$aV$B1Q>%W4&6`FzE=5>6p!r|O}C4(?RemviV=f5ZRB@}JgEF{ zrrlZ~IKrUJV@JPsV%voDE}UN+vZzNNI%`gT@GCrYw(7yS{lQRtk*fLnoI}!EB!5ax9Lmo*s*aaZ0Kbrb`0l0u?&p2#r*P02{P+f~Ku9b>sQK*|k}` z#$3RuQ`H;YjD_AEkFCgFT>dMxu$50W1%DQzI{`98q8%WcAY7PnNXrn9da^ zfmUO=)Sr+zqhwEoqMPRCNrP)JI=saqDUim!-u^kGt6qE@a!*?x4NB@Er885n(4eRK zSXR5&WHF=@gaezU)JOs9^y&u{)1mi7t)|d-U?Mh zs^#KKRBWZ@_sfJ8=Ax!D3uS7Gp{tH-?3cZt;LGnsQQ}E7*&J|Nb%!wC$l(2B>t5&z zd0Vc|7m4V2v^)+SX-OQ^ogk&!wrcInb#(q&<`Y4{i!X&J6R!qai5wRxy4sTR=rDqF zvW)oSeGSW^Yvi5STSok{1hF8dfGHBe=GY9%F)8(nt<))7^O{JZ$JH?UK zjtSaWr4jG`z65#Z8Bb!Vnn_l&o1;=cLeewS$2$D?{W_?@mP+cWmM$=7mlKZLMWvH$2;{#Z{IF zWSn*l86)Zj9>jely<);71hdUr_=*MRI12OS5u;S3gBPE>ckx2itdQR|BUqCZbjZ&d zWR(8X@PE#cwXpP5gc(KXF)&5DViuE89d#aT& z(5vPaV?-Gmxqjy@*=|pvJ#}7dnm8tYOq3|8i{ZwFqHh-?M%-zrG(R9xJk#Ju!on;* z_AR-=w-}RlS)6n8aZ^kN$ch-)^X8MJ<`lf(O~}A(Gt>uDd#v?c<`269E|@+G z=bRN7{7uX+flQ0zNi;H3B#N1&jT@us!NHe?7tLi4Y62OfOo?KOx9p+@wZ)_ZCmT6W z>6R*m#R`+c`q2=0aV1a&P1i6A~${#sH;t6|3jF=zA&i2z6k61v4sfvt0jvBZ0Q;B1Ovk4DPW2eXf5*&3!4@2MG( zVsSOiz491{0P=?y5g7ieTSXR>O_XY~k7PU$oJ81{wdhAimQ)d9X=n>Q{N77==5e|a z7V9Y)ka1JA++GJ_!xn2w&I_%wQ&rZq{1{i&CU%3^CMT-qDOo;7mM9aKLUc&)U}*l5 z013s5NAB(YPEUuozWv-gz*v76?Dj3_uWxI-D~I2f2;VZ(^hpXSNZ0yvadGjFNFcTn z1&9X30Ac}gfOx=TKms5UkOW8uJOTU@et8N=1*8Ge0YK;l0_1EU&jFc$EI>9O2apTM z1LOk=0EK`eKrx^MPzrbfCiLngGp! z7C%L2fC<1P z;3HrPFb$Xi%mU^B^MD1wB47#d39t-U0jvVn0PBFyfDOPGz$Rb|unpJ&>;m=xUjg3$ z`+x($A>at`9dHad0sH{`1pES=0?q*EfZu>WfWLqXz(1KDA^kGARX)wdz<6P%7P*t5}N{zD5o>W zRl^LU2i}LY$Q^Q_dbW_L{;bygh7%vfC_Z4Ag|~*o>(#>{@0l* z?3z~8qlfkEubrmthsxD`*wS%$h@~n?5s@Puj$$X?5Yt0qj>4p)#i1g5oZ99p5GlL@ zMMiTp9i2HjbBk&zQ6I^Qq^0x zjF;k*v>Mb7o(Koa#|^#Odg6^316)uFx#T0-G`q>u8r`^0u#ESp0lh4iS&64waMh@v za|+kk$klkQ;M$f=eJ5IMpJyURz8qrWWiESIYDlCR-B9keAvG71;y5r@!PhV)AY5;2?H z?ego&v)p)$D*B2 zSSMqKub|}iwwN|0T)>25Jij@nV2TJERZf&XgFFe&@t|{ z=EyowgcOiR5f_C}ilEk2qs_C#4>t94a+S)SSPRCDcGd|bh*Rwyf>u##v6-pCvlS(J4Wb0DF2omGPAR?CX zk5NRsUYI&B?Kp0IgrhtHGjgXYij$KwFmi#2*^_#EGd$;DRik-MfQV;hxGQdnzcx4D@V{-mdv zc|t<+-4i)WZD*>7j3KtUmgO3Vt5V|?%N41~)AhVr6fNC+Y5P9fMqZh!)BMGiyWtLz zV*b6Z__Geod#cCdNl+u0^su2uCK?GHJ{+5!UY4XB{zEOhPf^Wn6&0DTe}danMT_A63^NQgPgn2T}Q=k zlw$JCm)>HJwY9u8g}i`QM)lT0U-=XM)|bwR?IIK2$WCchWloncj7J>~vlMn#DYp^w z%f8*E&wx)Ql`2jX=-MsriL&4S;>?W z4c;sj>d*XL2e+!~8s9Lpyqe%1Ft?oP;fKsOf!i^j3oMjH-mx3+wm4DAxGy8T^g&#EEfHy5 za6V|L?@d7@gfaK~5Bs-wOExi+YqvOSbXI7l--tGU7>y=bw7<{#nr!ZnNGKAa2m5ub zMa5__{e|P79GtWsanK(JfrCudH>P$bMZzK?SH#4!tgyJE_+iuvRNFY1ux?VaG((u#J>+)N#aQ4!Kp8u)+--5dJ78h?pDOP zaAy=^F*VuZGgdNd*Hfb1jKf{$!444d}EQ%IY^!`dS(2iM270{oqv1G&V;>qOwdDb5z z2=2k3uUfJ&`{&*FN7ddWRd~m%BK6_AWNxHBzC-}$oYca&HHxh^%GAcD_{NQy#U7bd=>-mSJ4Q0J=!`+nQ**L20tX|MUC?QajyJAhO~ZzKO`yo5uCD&@;X`uC%n#00 znlEQ|nJJ@fB}Rvbff`VY&uaI#rFN74hmp;-gP{-9jUOmyuzvH+fNOB=bs7{u>3{96 zt|eo=o{z;l=(BgDMAjBXdk<{Dt$u~)N@?H zot*`LOf!8YCMr5KI;y?#zOV1>?2P+*Sm^F_bvnGG`tDxkT}W^xd$4sIjJ5iA&~W?n z(56W0jMJN%p%}z4>0RM5@4#%aaE5B}C4mp>@$bt>c2A#hl51MA?Dk|l$o%ngMo7+s z7rHx;SVl5}xzEqZM45iug+w|kEkgV4#Bag8r#OG?L0zkhj@usV_;n4jNFeRJUh+g` z9!M>%_QV?JD?Qj4e1^l}GBYz98)bx9%31&EP6>0CjFW?Fk||@)q68v`Is+>i^{;5l zVeIF_OY8j5VxuCzSLV;kJu1TlZPWyy(`N|B zMfciB!f;!4CEelYO1WpU77Szlj_$-5nJ7{5WzqWt{KUF#uufQ!HkBa%hN62x=u5R?#_=XKt9qP-#>0MfUy{-&?#b)+0Ste zE8_JkAHk%#WR!u7diawsWH&+~;*w&ugjj4w#Ag-lr`6O5^i8V1-a+BF(Hg$5ZAJEq zX-dkUeU_JfWprKZZ~bQ`qtZDs_GN4CYq8H<2bw)|RwDg;Ow3WbjR8PbD>wCDj~|!A zO47!$wG0d(!?jYnRz7&|F2HaKc%`wqO$CHJC6adku|leJe{m*-on=U}!dYVTf=j$a z1LHtzRprx<4`p(h_kP>;xT>nbG$y4t^pB;R2;pjD__hHi<*5}G!z4!WoHdhnOl0Q! zPllfliZj-Hd>mD&UYe1O$}C-4xr7KfS+4TtVIpGg5|7MMgJtH{bUl*TBw%cvA166U zc1Q~hOMa=1jDMyyZDo#1QSf2ofG_iBQay4)_GSnyUv$sBHCs>cxHJ!&NRqlTIDlz$ z+tUr@2G6$r!ud{rA($kMNK^VJF5Ta2`R-L*l(WpP2-7@1UJej+mh2$&A5pxnm(|lv zy58O)+Pb6;3%tB=SJ{#V{)B_JnU@nqClsk`mOokTDl`DmD{S?@L1ISI40n!lk_^~g z$f)6kU%_l4GD%QAnuz6X|9&4v-SpO}Xly*fGC0rLPWe$FqHN3at$|}^1k*Qy;Uxyh z6Io-qd&;e&>z5G6G>g4REd337uoRLY7T=y!w}$9w@CZR|&Jg@KkIm1%TY~izaGRbX z$G2Hgx%9D3;b4)C)JNjP*^07m~!u;*1KxB7V~mR=z#bk;8Wu>(zSQ+2^I5 za*b`c5*8UKmS@f$b$z(;DXsx48IW+9$# zs_@^iS!fv9NLVm1ekcDue{k--r+HZ722CAP4Md&x-(Bu&f|pg@_U~|a`-!hsvTG(! zytaZxR!@KX)?s~zgX}q8CI!O&J@Ycv>+qZXmg-mlt93ZF9R`Kf9_LpI!6yT3?GYIjN@8L;FQEi8!R@{+8 z8v;T``6&-<&)H@QrGc{Oi!eE_#o5J0C3*STYYmK-AlK0B+&?7_IJlpakf6p+K0`ms zuVh5r%;;(<4ONs@)P-H|{Mq&Gug$f2FM7+P;VgQ>6S#ff#JeYQKZ4~aoTSBfZMlX0 z_U#H~b!jA%!A?yDv zdtl7)VpCq+9W{H?upI1v@rZf1-{Y-0%JrqbscBLuu1ceGm`BK_b6z|=_5F7A{{1%n z?ARJFkDHH9erwZ2aR)^)KgL>pza1QIjzYT3eeQjA=l1<7Z6~axc@4rh7d*dmXAy+t zzXtOm2-u6Ik`3yMKLn^0m&6hz~(W3U@Mk)2u;HweTpI z1!Z-7?V7OFRHmDM4g-l7U9O7b?O1(YeQ{`e?uhOEsx~Zktj}~cZ2bBU!e2FqC$$1t zgzwAGE%z8n^^BX(Zw|{%gvB};%^QKGW|F5e;-?PZtrm!Ty{6O>}k;F zZI#ybQ968%?2hbR_hDSvbi;nI>iq>zn>|>9VnNta+UP?!1`n#rq2<0){;i-`Ta3RO zRX_Q)uT;JPOLg4LSlq0esBVY8Q^ODDF+-0lCju9&dpQE%?r8Tt%T-z$@K|p<{w1wW z10vVVLk@qfC&K++<-`$j(VQ|(C%>%CH_GTT4)e9w9z}aZaL0*!>}Q_dO5*Z=Ud7#@ zslTYfQZO1cfF2%|aNay?{*!k3e!nf|ezBoZEEaPgeEhSgs#LmipVHqwi1e~D{q)I- z_{9h7=CJ9icOlEY1>T?V->gEuZ(UhZPxUD~foBb;3K?5-2R1e848AXD3ZGlVDPGh% zxD4@3PyxB!$~uGCbr2&WwdJ9gO5|T}bCR3pRm}6}_qQK49S6e|W5X4-2AV>aq;i8Qumvfw1}<1dJ;CyN?$S|YZ8Y|RlZHy_HUL?1_^i# z##!9#yIG?7>*gOgGq+H?8ZHIzObgv!X9h7>^9Y!o& zl}98_S(f$qK80(n<7{Az{*3f?>S^!8CC&ys@7IMo3i4v~E}9fS+n%#uL4;ntaQO@i z`_w_h?_59WJ_i&GA%4v~K%Y=t9 zdrx%!X53a|YFfJ2A8eMQ>h1knFMH$)-~Fa7r8(BludA`m@Ac(+Jr7gTLaL&5uAr}o zi4T4;U%ZI5H0eo*;cUrqt@^Qc*e`;BkJV`p8-DySfRBM|xI;Khhwxz}^#oG0@dWMI z-Jd2hDvHM|k3N*hR66h%coHDm+IG;>edAQo-+Qm7Y%X^DuX}s$x3On!b3Kh%t~9Zt zwChQ`A|B|Uz-^VL7{aT)6vtU0`eFO*p4*J6u=uvTLUU3U+yuP$X zj#*q^>O?i-7j>E}5P>{tbx@0YmSRFsmz+wWO@B1(&n0KPHj;`zMVk-0px5k*4d*CG z`mibThODD0As-bk|Ar~Xg(Z-}p3uaCd+0Ub()cUlXH4_$*Zu8w=H?j%1qGl2dHc@? zgQVXryqC@juAjN-+ibolEKN|2XN^piAQiGGcfa`2UFqdDEFro<-%U#6H7WRVXy!dB z8m6qQOj$ZxO)IXXFFX4~-R90*OyW1@pK%L4KZQpm((5M0PG3B@q{uptO|{i*`JH!4 z>j$RM9Q&kK7MuhKzp;O#axI*##R+o8qVvn5qhd%!9_u$dyuLgr$DBX)25YiI9~g%2{0Zqo z@a9}iv&8u@A69g~_udW9g@3aYeVfEuhLt2o(Vc=dtYrXQ(fD;1gCgLcCSl@J7$hVk z;n_7;cq_iV8Ir})akNLD#gij`9|$2M8#=~cdTS8P3Rg~FoMt^}uKQ|uq8|ZoYi}P~ z$~Ssq6 z9Bm$MYe-n>bo1tWeQ+%5;PzbPvdq2kf_E#)Z+c(dcQBaukYro&PaFMj{1f{&jxyx$)7Y4bd6ywjiD6H8m5^x$alnJ5uBhL)0Yb939udh}Q1Ky$sF z(Y`>dgua@Ti+w57CGDndc=!d-zoVm#TwNF+cav>S`YOn<-&>U9ijacs!8CQBwKOi% zHn4d7oSmilktGm*{U{FWGpBRzIT%PM-O_k$@#yQ(_3M9Lw3hVCsa$AzbQpW&8yn=S zEgv5*&IoDmaa-+lMUp+?R<^dVh}~by%0&_ph$apQ)}Q6RHjP}& z?{h)Oi|;I?kDt;LJnbHKz1mQ9+faSwgsYf7UaTDQp0o=lIQ`gPesX0k>)p^r%PqwU@9O+N=qb=PIe;9=2t^hw`-fXBe=yVJh(?rqehoSKdM|%5^Yoqnzw!&V#2*bm7QFgK zjKG4Na^PgL{BiV&tnJLZOjMC=BAx5am%q{biSPC{dKcLLyABMcKJGmT<)%~FifM@J zhdYxalxC;GMeU{pibs@i(~{8(mpiZivn_Sgfu*J3A0E?26^i}}%q0H%;(5KnKKA2A zf#UBi8B$bZ+H!d9mh5I=sM)O!j#U9)(4wGJl7qAL1UfA8066zd`Vc`H?-lf6KTS|$ z$8qJ}9JY;*ftSDx)u}5%^z)w*HGiZ5^_aLN?B^lGFNO|XGd2~%GI;fkKt(oRv}~tZ zmYr=@hCOEikfX|EVME-%iah>I`dYalyw!QB|Go)|@bL$6A}t!0a1GIN!MrZuM-dbQ zTF|4MQnW2-Q23QdXLzN9Z1Y{)LG`Wu>ZQhw$))oj4}Fif;-y_A?7#n@rHPA6($R?y z*8LzFQxVY}F)wm!D&2ioNzElWM1itCIYRpd$c_aS&QDHG9AKoD6q%*ulQ9@wrs3CV zpgt-+z3*yw^iuo%<$KHO<=bMO_GP3eU)2+qmp&stWGo9jhdjr%3*cr7NK&pUTj82m z3$X`dM;k+Op7T*ATR^S3C15+Xvoky(K!#=L^5x4F6%~(y-8?*^{%cFbQ3T}?`LkNF%6SDv7Z&FB0i$KFVQ&Nalp-Wh z2Lx6EDOOI%5ZJpIMjXW%QRo#l6W~Q~gmJ6-PUHkkpnko79q*J<%>&Nrmmq|dlc}7g zPu)Qg|D3+uyhLyR5+mpu3a@J$53J1O!o`R_Z|lQo8Byhk;b}(fHrcMCmmlgN?s>-Y zrRR984oDw6r+XCFt6j=Eu;Kt#fsi3wYD8F^6zFvWLG3|V;7u98b(GWXyvG9Q))5(rFENZLTuxDPeIkje-iHL@~u2{-JD zOncN1S33B!(L5}$B1@qIlDU9q`65FImLfIF61gJzo4TjSJ2@BFfoND;*I6JpI&dN6 zJr(!_c`%jT{Sf(T=k~Zf{@96I8&*q!Cpp+kRDy%aDQEZ5{?E?i@1rKskww{#;E(H0T#72W0xSvUMejvWmS zIbHIjXfYv9hr>*T!4~L11BJ%3VOI>+u$a7Z8f;40HYmaQqJrY?!Y_?`UZD*^Cg8~l zg7)bSe#1J^=4xU{X$7FJ4}>PcsMdsqF3x#&tMnTYNI7@(w&# z%4RXOUssNPx@v2$Guqm?=9_NCHyFGc97k}_hCDp|3R+@J>;nf6#1lDQFsmCU6W7Pb$~dnm_vd0|}?*ED-1`|g$Zs^ad_Ok z^2r-@9}Qa#564i`%R!Ehus3{v)%DX@B;LGajv_3}xliXeHs;Y@e=F|DhWNdgf36rD zTl_fb=}{SZVY#mRUf4$U6Qx&&MERc z!&If)#Lv?PSvix=Cr8G%iIk}FU5~A=1@6rX6@=CYwp{`*5C&q%QRQx2IyZ1|avr?= z!3`9iICrEpJ|$v{i~YSJNdrzw)j`+EE!wnb;%>mznEAG_fU#^?C=QT0~#FO_pAPhHzLQ3D^X&NN0p)61fpE}MxLTcsBhhRMNwO6IM+epSKIM0o ze3aul`lvl+z5o8w1^G&|rGq_D{X91rrBQRvnYn7mD#2rte)w`n^oBRdcS zM^RrSeZG`TL>{fg0|)*?sycX_FZvX(E)I3YxJ+meAUmvmU0WHdYJS$9cFMcZgTX5l^RlaF|T5OhgKIgKO-`i0*V3g zTfi9J@uPKH{VgkGM;rwo^wwfOH^_VUUoRQo^5QEua#6YLZJ*!$=ZR8%=UDWvAr8JK zjDUd7F|2vrIU9)p$KW;lv>X8$&+TvAzFlPc>g4KG>ZGI(nF_C8kX|JAIrn2RUpd~P^u#HU&JJs)X58l}s!7gl70I;ThK4cyn#dnA|+Sdt|ue78|^`kN4L$bVkMSu0;cEq2_Yr#K^qfx-I2fMs!;V-=F@Z z#QKb0+nrZQP-xFYp`zfs&7(f_$(m0JhLOg*{2!H}2d z9?t#4+JiJW{mcA$S?&G@4zUaBA(|A55B!|X`KYQD-^G=n0c1=n(LYDzI)7w*<=260 zle#E;0Ml1x^;ONjF||87ykR+0hRRf*Zg2kYEdZ9C&p=^wS#{~io^0uU_`%Qf9#6{S z5Y47zlDP{)WWBcRi}ro%9xsm3M?&mNhEc8s&cq^a=RNiBS+%Ymc02mzVjDj9cG00Yc5 z1!z3}w>g8{v@9uGuW0MKsC%{~^=#>vu;uS>g0$mi|BaSJxJ0EjmAmy~EXS20XHT7H zOqp#z|1N)}cIdn+&a3D$aJzlAV`y&iTK;fhhRa$l^(7NyuWbi8=ef zfzjrKTUC8b@d9{%2C!74)+5U8KC4!H!LIINOX|svHubT4eA)x_yKavgs9wCNl@^aS z*y>;kDh9E;7=(sJ0P3F|g|B~Z6tl3joa5@JbisIKY9O=gN*Fcjm#pd>ZLh`8{#!qH zKZMTd(@spKg;gfPM??+g*h@lIo9*D0gI{hJMhksC{n``qJBsRb_}M^MyK?_KR!z4c z78gRHU$KZY)h~Q1ORlPv3k!L;N+YIA9r%D$X@1uqz4sh&`+UhwB=DudR-YgmRv6)W zmnVo1fuSLvuM6M%%z!YkRbTFt&J&D`RfWY@M36lGwF8bR(rWCLcZiXZWS{@Ih~`M& zGW_3}EraMR?z!>nC?WPvCv+xIFo?(E1}b-Vck}9K_q7v8f0tPJmOf3&Wa?Eq{9W)H*ZEF8QA5f%X{?hf#P>BjSKp!UVJo+%2ef{ zvoOSEcI{SPZxs)YvG0Xmf}mPD%lEMlZayw{2!{MOv{3l_P6Nk!L3}U8BaO#iNY=mQ zf6UkRw&Wcv*yjPwJRmGKN?2KJ_5Y_ZMn$C$PJ#voBFYPI7h-44KDbVMpz;-KXnid# z*M4?KQ)QMuC(G z<{4R{*3JJfxTcxMWd&PwQz$1bqYKy?0phogdvBfen*ZoE`vIm$`*k~g@3gWL+z>{y zb~*f6u)WrTcfx;*a8R*{xq@QQ!OD1v_U_J3u9eI<|Iv!ofku#o3p?lSa6^ClAYYpx z3RMkV4g%zHH;9}RVnzu;*90Bc;bYG-H6CA9C>d0|SN8XPWv(^-KvvBA?*>qc+=MH6 z_vM{~#c+u)|GUQ5&;OkNTvrTk6N`Au0`9qAy~x^$1xJYbV{5ey5{Dym15=1**8uu| z3T6)L#$+kX<-P&oDJjWluP2uUdYEgYHvKd<8H{DFrp@uV@>2j4PORz2-oAudF? zLJ^BY1IRnsX+&iuIBK?Aj>(Y6A6DNxzo`SJJV%*5^+~ zuK;_7KQoqfuDsc&M0w(8$Q2PIwFvvd?obMqlRVeV8!gj;2# zu%x7CRpVafTZ&29r|~<&2#ga4v4by%irjcW_|oZjUy4LAqG7{QuWv#!HzvAPe7yL0 zcnS^W~ew{V}9t%6gq8MBmCd_vZR|7 z0om9BB^M=9a6r_??~M6>^rCb(f;Fq>v%U`q?-8e(&WbnUG9! z&Y8?iW}fpLzwewAxQ{Xx?Ai#I7KiA8kOqcb>2bo+G^iRfy~VY^9w`CJr~hLR>3a&8 z`H&bo+MdV^w~W|PErj5Jb?E< zL%r9DGjRrU7T=dJzNqEz8!1LmZB#$`9UAx=&rI=f9Y1c-AmhGxTxuT?Ri|}55)I!M zac^XG?D0#zB=3`mT*m=j83JXT()c=hm)#Bu^=3B?kR;Ygzq{F%lTVGhlm=YtOis z3d|5?WWZZ&4t>WFzAoLpH-Lq1;#etO~P{7hOr&#+_?KEtMbM4Bv3TrP0=2H7Isqn#TQ}gaj3}@;aKa z=B%$!MqMG6rJfJY_8qJUX>U}{N6lhXQtVsj3Rn~-9&%vjlH&C&I1`QuH|eW1G8~kQ zvpH5`2UNZ6d~3kBH8!-BH8wl@Hm+Fm9uW^+>BjuBcjGCrgp)u&QO!oSAK-q zGI+tR8ABnh@`_-|o<=lc>mXQufm{}%d%}9q;tCx#Q8x!0*DKFcvH;_XnW`qLPvMP3 zJ%=BMt11=AF|?vpn-g7$^YV&mtFIQFp3+}mDzH6K$9tIAVkrz#Z_o9X_eonNfBeTXq&>UP>BaLVFRz2;toyG?QIB zldbeEAse*>O>YfDZ;goZ0-5pTn&s$r{IoTG_B>HOFouAa$lr@72ui>2+CGWUV1d9u z0abZgQprl(6YBmUG}$9O$@TG&`^9wLtHg5hw+1oFgrG0K*+p0>5lu+5@86E&%Xv2# z7XQYJvv8jY|JuXbjP;U@kF&X#jzXTN4d$q<-pKe`@88@7#xGa%tFb){Ccm#d=p09V zIutrTmPa^qvUD0=Zef6PTOZCOUnamv5_CV`^x1FSW=w*dzb*-7$KGcdc6{u#PqI{f zyv}@^tg(IVx7jtWi80h$_B>+iJ51#wZf`uE+LwQP+qtIc-Dda+*U1%djGRjt{y1YZ zhIUaUS!2)VZufFU(4h!((Sv&xrunMre_S#E&qAg4WI6|FVn3FjQk!sJ8g+hD-i<4? z4VqTBRN#-tS|7%Xv$!4M@T97klt}d>iu0Rd@LxQRV={d5^V{a^;2yornX%9(VAnNRVci9?!7S-eenG&=%5{Dz} z>B%~77rY$`uEZLGzeYC1g_{b9Ip?EQi$l-77&H#Bw?bN>H_n7D3^z-H?8umVpT!Ox zCx8CXTfL9@sAe~QsTm}>8vl&P+>@4jtHAwe%Kdo234@g$vQI=N1UE$&950-Z|8h1| zp@hkxSv~j#LkZs&vOXtg6M#12FzMX3^t>TqtiHZo1O!}<(BycZlv!kZLEorj5k>ci)~*2u;EGb1BfU468^UZ$;+L$HUIoq?NJ+cOg82UA&KnJf{Q=*V~hdh*^06-776=4_c))A{9hGdDKCrIjDUBYH;`t zkYiwgKpq%sZ_^*H3yua&oeGckC+qen9SH(=bOG8k@V?L>z^wt+l=K=bEjO4|*b=YW zz8fGH$;#&=(Y=$G>dUJbvE0ugY-@M_XnPRktFvCMYvJ zq*m|4tB1&h=Yy`lhBfcEOXXFD)ho|KR<5D^LeiaQ=>C?U(!=)79z z(M;@T0m#Nh(!3?B5~3Sh{d{Xfw%S~yw9E6nKvQb3cKc3sdf!=xy}0uBIcN%Vno$yB zkHSFBd(rya+&;)9;BiiU!@jPwO6=Zv!Onmyf%#A5W73&?KIp@utLs z;V^Jx#$#dt*zm9VdU(r^*WmoKv(Cob%E3alN$QY^iHYWBuEY@l+hyI9_7fK2$;`}b z==blh)@X=Lz1Kv7J%@elI9>bC-EsX2XnkQ>eNd1=Pmo|j1|%@HiW&5unZSq z7@lFJ?w5WKEJ+m zNv-m+T3+Fm6(skZjl$V{og$VM@SP?m>1+)(x_9in>O13JkP^Dyy5*H!+-bkr*ti`X zWkS#hfRFjslGT}b3dfG7e@PYrV{QME|IotX8~ZBqAdJWK@^}M05W*2balf~*l*mag z0$kQD9DHlv?jBmY?l+o;F6{JQ&r^nAdple1?jC~d94f&C+!(adH5i|^W~oTdJZ}cF z#uhKY2&$IddL+N^lA}>HN9adCuP5Rip5$bR@{H0<{ZXU3kizvvb zuj13l!z^r{rk|2J=<0HM=gVRA^jIaITa@%kwdZN|-6i9oQTx3L8QyoaWDam_7`AU* z$CLS5ph|eT5OJ^^eN0`;4~sSmo_Jrq&HxouBZ#|Z*v+)9=->wA%9B(+j|mbz`IcX1_*RN*+yTvnowlf~sov0Br0|I!4r-d`aO+q%wg-P{68b&m4~PYyLXEw=-04*r)j37jn5 z-Ooddn?G-U`LHl~k)*vGWO&I2p-|(D3HW+FNg`}KJ;tC2_}L6}d$jnq`ERBZ{eDCC z8p?rZYRxQd&8`l265e}aHwBR>due)FSttb^TbG~fVLG7_wPH5hrA@-* zWa%~gZw9OXJY+U}cs;$~e>+(Xkd#L=7P*#Ne=d*l|Lq^?jYM27Z1BBN&zR6HOFN$3?v8%90Yo700bnuMU1;2#( z+_2GhNwt@&J|P9dz2Afj_7N75_}!vWlk+=nfxZ(DK-^A=qKs#7BKU%Kw-f`OXAR%4 zah71xW^aKq5A!Pi$7~M`&Ym1GADYAnt6>_9y4Ru+CJ`V#chnaZh4}0r*(Hl6DzOC0 z8Zf%b+hu*+D(UgvN_`M;+^N*GIgBIH`5aD|`*oN@0FkRjwGj!QZYhTrGOWdYox@|( z_Oxw&!3SZQ9?Y+0rRZo#c~5wvFJ;1CE^TIRMSF8iV|6LN#%5-2uFMTOxmluYTC<`F z9xLRVkd=6{3cG)4MbcLhT5Oyujni^Y@1kajBKFcdw~P$$s=U5nZ##K@`(#k~urgUl zb+dA4wk@}%bhgfyc=#f;qa<2wd4IS|8mJ%b2>t4eRI}GiVKz37?5$K;d3nVfT8nct zM%LUJ9dblnRatMPXlh6mjM2t~$j-2MQg?Z7cib%n=k54%c1`ky=SqwxKQuCb%;8tD z(3lFC7eyxsSF$vss+jF9H$gX5r_84|F`r~Oh6nx#oJXsWS4nQ6HvUuDs~^@W1T4@PFu#B=&+#3S6!-rV7L| zq7B52LzQY>w;F1~XH&KwZ^F7Abr1OA$W00ns!lG*{>q9W$+I!gal?_!s zl&-ap5hC3d6$OGVZe&FpQJY$o!Zt2Foi4GcpXc)aK4nB92xY_TkSN{u3c$_wyf`hs z3AUZSld!+Owg}dP0(Nvh5MED$ayH&To$4OzFQ~=8K}IR)uR7rEBp8K8=3P1KE`VeF z^`hYW6aU8zQ1}*O1K!_0-bXzAF9!l%&Qad?H+vpfKJK$V9%??W0zURPKPG!#SM3IS zcB8=G?*!jBd;A^@-*4?e-ii-3=ffcI68?hlracm1n2`DGV3oU%@*mN3FdcPbQAbqo*I5U11~E~1&~^BMo_r$q|m>R zJZQU|!jyzgsKY;;DxtFYl|??Ai9 z$(f588bx!(jf}FYQ8F_tP=6Pr#8VJjf`LUM6QWG~yH;;D_I!70R)43}4vU>H*Njap zdP@~Ia@n)WrG!7~`pM4$zU1QLq-;NK@w&wS?(G6$^@gPH&Hp3*N$iK~YW&z~nu+^k_&FRDcJke2cL^5G|b% zZ2-1TAx!Qd=F>>2bNbm)o@h8N!&x7T4#W|d>Pnwl(*G%K{G#J%@ymg)6r{Pd?8o5w zt)lD*@ixm<>^6bwecMsYe=^bwkW@f*&^KtL?UpwPMC`T7FVNkW7R(XpR-k8vx&K{( z!tX5wAB1BaMFd!1K*|!2Dbt_cECgScCj;JHB;b0U=WB2oNc;4J!1>pf8>s+a{1M&3 zRnPrk1rvfJ=1%8LKMvLF6iq!Uh@}1a9YG*&1l$-z&Ow=&6=H!p&yq+qfCKg`dDzsj_bcqTxDjMy2%?x}VjONQGUj5s z$7QpwqRq~FD7KaBQHP~pIEIzp!Gyjh$!@F9;jN1YmvepsI1I=oibED(`z4d59VT=r zepF0kXgd4SYwpsz!FZs;26jC<0>w8s7ES;okI)DM5(-LK-^jT==XH(8v4)>Eezg`hHv|>Cimk_Qt zHN`J5au_yk3Si0y)|ux!szd+zIjApLf0gQl9v=nuR;0*^9h6XC*Kgm zcBlR>g389oBD(t#Gao*b&SnCUwYL?BrMEfBCCqoDRT6%xbLyWv3M12HudWysEXUfa zSI23W+R2e4Iuy-rUlX5#76rWjf`xPP-DSHZwGWK_2*n{W3FHK+gTewMJ|#h@L4F0N zMWVx#dJ>X>Bj;Xwk7=`@!^_MXWA2JX1-;B3z^-1< zjff6{S*F>b{sQ}z+h>SLK!ET9;v%&sGN52#Vc`Hr6ce%$>MsG);2)|XNR)G5zMJuX z1YY_MljKoYUcg0OO_m34k#jaf1w(t5(M~saw&f=go@zgZ&BprQ794APR3=o}aom=D4bvJyHTU_@nt zIAAk5zOQ)S)@%fVuM(k3OvzXVoBb627sr&q4+ymhG1UtbK{=p32u&G+g8HR5?K|KO z>L^eE=?mUVEM|oF7t~Bf7-orKugI3(b841PvKnyZx=Iz;?cI59-!ZrD(l>pI%))2j z)%oc8mIs*&kBcP4D35zi|5hh!dNd+Ql>Mm+^L`e>`uM2b}67=Bvdw(Etl(@N&~8PqM9!TzMbz%;7U+Ruu2F@$VzBRm`XTG_>W0qsfAX(kVZcM zr?-e-K|~}|BWaRNKk>+^{0{4wt_-nNeNEj?myK zSy?ZWHK(-Cxhq4;!l_e-dnxjN@5r<58d1K0lB3?mS<#e!U*ea|TmOPjJHuxJZGvB- zPVg&2F_Pn}!7KLL){@+W|Kb;2J1dZ>7WYanF_Fe@}$}7)%rhLm3 zHYLS}arf=r83FRGDb*K4Q<|-PXLXLP12=CH4GxH-68jlHDEI^oz;An9lR-WYcrZd_ zwSCe`Xuw@_%G=R@K`ImIGml^yMF#`41}G zRe&5&TE$|2(s{ z#efn-3t0+8ex1fgwdyVC63u6^p-u=&LJ>=imx9aB>$QcN{8r?@IY??*AvM@DpZKS+K@R>TG8%{%@1%t~ zONI!hKnF)aOh>pSD>#ey%;(U)5u>xu&c($Sp2Xr!^vq=QETqx9&C($7@Fo2kZv&5( zs?kA&HZ70*g;I_3U5wdRh=CF?0Ff#WO&mXURos27l0A_k|I*D9OG^AQ=&;2gHYT-Q-VXy8#D5uezXq_khX2}uK?X#jEDrbMgt z$>&d~Z6@Lxm5T>Z1Shbho!K1qQ4}N50f&rhd_#ik%C28>xu4^IFhb^v$?(_PM z2)*tgd&wRY*EkT|onrH!r-&TcEhh-i$ppb`O7L3Z55y{LWW%-m;d3X)9PRA|71Iz< zkqs37C!!{Q4WHyiN5gd{nCTP(mnTDL`MRisu%wD;pY><0ci-Ep7RH58BN?7yiWDRM z`=eq-NX^NJr$`fXGZ{u~8Kp!~XeF9xNVVU@IL(xQjUT5+R(EaLGi9D~l~^Bok8GMr z2PlCH@oBDr*K}-OblhBLzMBf&vS6~P4`7F*9SP@W)oBik_0)xhAm2n#N!_;QPDzdn zu6@o!$XE_6^0%}txc$Ke>c zNL0f|57yVm_X+15(u{|K2_hV9Z(CoP2r9JbD|p0n>WBmiDZ&$z+MoiN1(_bdHsG?4 zK?z5iD32|W*6Db4)Hey&JhkeNe_HY5PA=}OJ*7TNDv^7lHy+Vzop%-1bNvcbKeh|I zc3AE7q(QCKtEDfSXF8~Kz2`7`_4p`(n$2n!RN9viw#4;G&q76H8 z@DTbR$jqi!A8s56$=*BfyB+$G(Ii}U~LMlAmnC?C~_m05R zK?aHfz5kl&)-!oPXXr>A=)VV)kIk{Z5^WFz zrlvs%T+Y~tQGb5NF3oj&Lj^#upemBw;g4bNB3V@zv&$t5GC6ef_-S@tJ$BXJkVpwU zjGJZvlo%ilObz@E@TCO()+7r6Xx{#P7pZ^;*A4F){hu2HfI~L`e4M{@!#_d%PvzD6 zkHMvSEH1SdfN20gjVpizX6s6Qm?RLW`~cS-H#i{hhyJ%t$p6VLHWiQ}wnpR~^bet} z2VVW}YNu?O=u~P9^H-5p3KIpr4Q=A!s62z`-gh_cF0yXX6{rRt14Bb2y>}j7Dl%~+ z@4PB)$S7CGwCBUO(8whmKnpE-V$zAT@AkW-APsZ<@4ZNy2;N1<-|E+i0HYrq%0O}Q zm>=>S+jiqNh?Kr@8SDLPy~Ym(RDv=M?)z(3%;f@|-CpZ$KipVt`qTrNys*|2rChs*3|@y?A25)c?dW z%8&vaoH)v)-f{nz-GFou!_4lX^M6g490nk48a37kNyz`0{r?yK|BK}>KVZtQn?-Rq z?Q#CmLQ0D(h*gUi1v>x)nqnYRP%!g6)xZ7!*N*|d3)V9DGWh>>-~Zb-3JCJj9Qa2) zB>W{Tum*z!7V!W0IuR~KfXyJ_2Lc8ExBSOJ`adkB02ie&K-l;n6D0^F_-_*w1P0I+ zfo`~N%n z-|l}Od*aJTVBi1q$d5=R1xX}$eBdTQNYYYbD!^&|z|S7`pRielvEjf9%tb{~1XMji z_>Z3x(n45X7@#7JMR+xa0@84fQra#6O(wu8iaY@J+o9AH;3Gwn786$UH2C}G;fX2P zeGxnP;N>5%=5x;LGnu{K;4@L@vG{8#kbTK0)2SCXdIS$Kf>3?}4-QQXm7D?&4l2oI zg7+{JSPX1zcC>qYdrK4qazw2vYAyBDAMzPBk@TUeCrN<{9tWF;ZDH_{lU3%toV6X>6D%W$pCs@onu95hdv zI!ErSO1Bm`!c}h}uJx11y3@kR53zJ9jyuHv?WK~eE`;fs@NQB?Jr?n^R>Y%eI=J?aq6&2xq zullyvAPe`JAvTawNu~E3UAc|opPysuQUmoeV~XxCc|3g?;`+V+Jio?N@aoD;@aphz zvSja3#$|wu4S^LQ+6(ZID{okPi%sgeC2)W4Ws>i5q+Ps`E6(W$<6r1CIl7sk&)cqoVkN*fmuZWP%sHmQz|& zxQ0QTZcHgh2(!gj;u@NolGgIcm3}HiOlTRZCDszKr%MVg5iPT(=vM6;aL+3uC>4&_ zVNCsz-Z{#dpN#c+sCA98jj(Y~u|d^GBCr~|vR2TQbeD}SF7(t^0l53CLUa;V`&kf{ zzF$sualW3ORxL;a7b1gUbps}0y^h+-R42nyl9Nq7X*0!F`s)Sn*VSVC9;ntM1qkqC z$O%e=+oSnWjbNf*_UtIV3i#ribubXe2{Q1*NF|1@uett5&7(h$P#h4KY65yIQ2+md)w-TKj9 z)Htq2C;c)|+N;#qyn~v{wuBhllAjNLNXy7LNY~KNz|PJdkA=z(cu$j&kqHP0Ff%i! z=mHasNAS97Q2)MjQ{aJEaZrw6hJm`xuxltus+c@M#0PHTVm$Ad5tQagyuIR*I>{z184y*F8|A| zzA6A>y4LFS_IwAxS&om6^xB;F+5UI!EP?mV0VG&JA-h;>`)Xta+6pPj&dv_h_4MSS zO-)LIOjRbOt6GPM6rm_{j?T|!xtEC7>81Um8>KAtnU;1KxTC2l)WI*VM^ld;G&kN3 z*Pc?3pG_EUJG(d^5oyo)%wB!u{s0X8HK9<=4x9ehd(w}=)YR0Zbk<8kge&yZwowZz zLMVR=FDb0%-=A2c@cF%;trox7p+hBaN999-S+oayyaQ-fq3XyBMgPm;%C483ucCJA zACxD-*~(2SZYuml<&PANt^!1%*-ftWr8Qk*BcHQ5MYGlpZ%WH{ms#hRuA((x8YJ%K zXMf!b%%?&{@O!;Av?Z1nk+{7zh^OmxygzmB$mFt3U-MFy4PdO?+~!nRyj`mCWA7Cn z9yh>9m}3YAVsM#VY;-v)knnq(+Sr_KZwJ8(tS|}xckhnmRupsq2Q7GPY5l`tOnyKl zG;dHxE{pdYnnGAL!(+?Ql1Kp~p%LqCP0gGB=2B;I5nn|)Ls=txStUbTB|}jsUlI5T zUZDzux2O7jp-i&I@@#CV>14x9mI@tKeYl)Vvf9RYMI~QdC0|}6LtZ0$cOiRqA$xNv zQ53UfSpKzc?(l0$MCU=o+QDTXZ3*v}5?(~|NL|v(%luW|uu%rel62MYYOY&r)(LQ-lo0!L-$w;sleHcYa6eS{0qfv8YRYk5${iW7;?tGYDqW33Hpg#Wt{F zBJR}TpV3)|Dr#;oX>K1G<7}Ge6jxxTt74{Oa+a}olD2m`*Hsu{QWAu#<%{n(R@KoH z-|@F|Pfpd9VOOS)?>K9BENZ>fxQOP;`NNe{>Arb}EJ#~2AXvf<8vP6Z=P&%|ZjvG< zqq>wojxv~XshTmAzLF=Ia;V%oTG)ELcxQf8JCrz%2SOCx`Hv#{c)IFFUE!;u_0G}u zU9Y>r)H_OARTJ&l+`@X|{Oh1(y^R~alhZ2)%YbI*gXojNP!Wr8bewP%&3tFga2fI! ze9adf%@=RY7ii5F3G!8Q%~fp8)dhjVON?%E{`>xJ9`GNkr`DRgCYr*gh6g5w{bftb z-Mu5-^kl@mWj22&XdP;-PoPIZ95N~t6cl`Xd~@f*DvyOnuHergAtO{)OuoX#9s_Bd z#3{+x4L`@!`-y>)FpKXg!BbO878Vv0C|UUqwg3$%mf>2q(oDP*>u7vqW`ZjyI%=AZ z+T7br(HpBKx;%RW-Jj@I#=~3P17F?DLr2`BTx|qvU2MOTR*p_ONLgfN2ib_DI4+Ju zhLkQ`ncj@m4t_EWR>}v|;A>!sP&YSHcfmpp6TMQw^TpGtU<=ULpTRM@IMl-I4Nc-1cD{J)R?#!iqQ^ zq#9JHg(g)FQk7AGN`t2yib5>DrrbBCC#Nf2p^*+!6Hy6PF5h5P7nu?6y=`NS8k8Xe zMKiw`OPJZ(=5=wZ**fT(IOv}kX`dTu9~)`^HPYU-)IPOb-m+Y#Rc|QR-=aDTquAo% z{DD1>jGcUsZFY}Mb&oydt|9KO0hLK_Vv^#A5`902)%**)8GFGU+;Wa)es&ha`TR<&wMg~7_ zPf1SjQ>3ik41UBuA0C^Iwj+|B=esSQm(2&uOuJh@#zw zblR>FUCNqU>KYDm#rQ8OKY98jZSJLP$Yt!DaYmS$B6*xLxl6Wof>giM(l+z(j+Kq@ zrVrDVDe_Wt-WB+}7fK$4CSIR1kI1V{NH5L6w%sP!I2YK!Ge<=jlu7Eazu|yqJG0u| zj9cG~+dquiKTICO4)0^7tqLbeVp6I&8b~?{%;Ax%Tl!mQ1<7qgWvQWsv58~5OJED@ zD`A!#ndIYo4W+o=Y3NDgD3{4yIl`Kf6Wat!UE)Hksc3uTpqD#cGXxvvyB6iW9nV~J zmq$ncY2sk0O(qIx!2tZQ?@1)QeLX0R8A*iPu z3f|h<`o;IraWshzg*d%9rTG^o$8Sthn5rvrwlrrf-wk#sIjAC3$>dtjWL12%WvU_z z4|6PKjV3kD_2svUc0M1+{!hn!?Bx*_QS8^OR6;aQdAxG;Frs|h8miw^qJN<}B&nTH z-0*(8R-iR5B^PQS=&vUbG21yBp`)z$1epUrYK@qpsiaYm+gmA-FQ>5fIjk5l3lHfX z56Qn1|BcP_$(%z(;F!&;gxk9W&1)M2L^VZunypqAL#)zP!qr}K=`3rdM!$%;^$kOj zJX`5Y32nL9Nm!>uNuk8=L4p0aB_63e7u3xBmdr$avU>iyAlkA%Z3AX$q&UYQ8Kcpw zIT+UDD@-XW_&{ebsDoyRO5rx5&_b24JvX7eC$_Mla`M{I($S#g%Oq8`c)4lutmz@P zAxw{`t8$P=c6m~jN@U+?lOY{_U8AgWrbC{ZBVV@Wot+|1z?+wqrDb!ZFte$3oP)KJ zrL~f+xzcDEKqf!)CwJvfZi-aThFp(w`KqJ>qd{{R{OJ;N&%S5D@qqViIH%aNdhs(> z@$-K1GgW4k+#Q14?Ty^6OYZMy?bth65s^3yJP8DynNgh}&fdR+kr)wtB8ccFd24HH zQ%;H%_Ync$h-ir@tni--Ey>h_l~?GaxYS(#QmDbd82zEkfS#I*+F;0T_fFIJX0L;rb}p?9h}dbIk_D05@A zx#+w;Z)dwpMTd(``^__|KYpjP=So6@P`dhFArB`Haz@D6$bQzyur-~rrHB>G3hk5% z*id})G*__l4E+kBG_K4SrJYa}OLO5nc=(ZWn$bP6#fFm*_DB&ng5V`B@3bk!73;Gyk2pW&?xCA>xo`% zREro?Xl`xdj^Nzb{sK*utfZnJ?$jlOZ>w$4 zEjLK^IQVPKT&?;*0ou|i>Z`I2(QOj*Zi40}o4Was#;H6d;>oWqlK3!>={892HVErB zXzMnJd}k_^`p^h^uln+)%lq6?PqHz(mGpk8;S?z7tg<*mB^eMh=Xl)fH6i)3vTp9lm@$k8 z>>sO$gnrDn>E?#lyOkQ}z`2E=J-Kxpo>alWw2I!PI;L}tVE<8D2e^c@FDw+fS(5Vs?6=~ZRLQ0XH z70Zj93uFc@h>~r{)ezd0sOCP)?k6e9V#X@M=?E&N2;waf>RzwTOv3dTTld+?-ch6W{tm9{Q}C6+9TnK_G{DT@iTMFs@wS_Zm2 zKv$8hW;mFuY=r`0r2rDESu&5aC$91MJC^Q}!r)y-6qKQGBoDWUf+zDc_Lo@U^6n~& z4H}XIA1_LSjx^Udlk2r)e*d0BpNsJ1@z zYNw!SV$vT(`(qPDZ7oKKyw&XUa1IdsY#kTk?Fxkfvc?l=RJAPa01 zjP5rpa#A?b%jfiNYzQ7LE-v1>)lC!tSOMTBE0HG4V}`50|0#?adEV;+exK5Y*;;|{3v+26?>8kVT@^SJC8Oj^+1{?7j(Df};sm)Z$ja2zz zEv-n%oGY{u@H$(e5{KN9dD0v$k&k)HF}XBgmgf4fgJ|qLUDUKOnnpTJoz~zprq_y9 z$Wm2gG8I?hDv__A>MunaFGXrE&ezgqS78Y@z7geRoryN2EVOXt_erA^b@kebxj+z+5UF~R9;^{hJ^Y08hdL1-|k6$m=!_ts}zU6CUAF)K3iD`LtMQ6(|rd`Z)&KQ=M>qcr(W)LmGr zf!J*to^U2tR5>XDW>E~*e|7Dg#5;GsUlP*cw7VYozZ(4bDf?&0#R+GUO7Bam>y_U1 zK096Nq^X`jqT9Y4a-mCcplaPjI=X_H%KB21q?}5WvTdJxVP0gNX3&HcElj)f=hN%s z=&=%2<}8J7*U!=~w!!zyJbxQLtys9|WyNC{Vg4Yk$%GD`mL@5humoaS1C${~#f(k!Or~Y#BrBV`7Qf|BNOZb{~v@!yNtd7L64@LzyTA zZvK*Wy!zu~JRl3)HGbO1hw#7###YCMQ#^X^v=673F^-|ClBuhcC=WUv>+cr6v8B4C zfg22%B@z^EP5#P6_q?(igNnRlyjmD1k;--;(bN3i77vs{lD@P;lqv=j&wgDz)br&ynkG7Gesr^?-`s+EkA`le+tPOZx;|YkiDT+2MH9$t);i*Usjmkx) z>^dyL>xoiR*^5S9#6Vh$>{@1TKV9oMT?@)f2u}UHlYV{2tL>L2`p|X*JOi_n*o0c$ zYm}-jRPt9_DrLE%5UKlVEH!sE^_pTH5-V&oXV5<~xN!P;Z~4JWH9KPY52ZYY!jzsUnNx?t?flu2o{rF%E98g1JfFsv$*$KTk6dVW zCbFb>Jjj)Av=R>LIL5!?>HMzGMfiQqgJr;@F<2&6c*^G<^0PnbPV09{0)k{7xk4Du zj{~RCc1I4?Q_J>+X|?f!$P7sgj@Vy0e8fKIp0{ng@rOSwc$a~?Y+T8wgSa#Z2c0#%e>OS`B-P>Q5qf5|7Om;c46S8%d{D)K# z<&F7|qQsn+8=AXHQ{in^5v)n4+W2emfw0#j)sz;4W$|F95JYApLrl`*Op)T_PGRFB zqSCJZs%rKWP?ll}qMlrLqBf#zv_jjS;91FW0r2sL&S9jRh4ASK48DbiehH&>$X?%* zwYHPBkiAr>l6)w)8iFeaG1_GJu?-b4HP7jjWo>!)2z4beMfb$iCj3%(MW)S=)jsVb zPb;PKtE;7FNj1ltHOCim1(VBE?W+MV5a#k~)d6=Jjb_?^#hr`q-` zd8mJ!alXj5Xd8YWf1WX3NOf=MZhSi)8@5S}Ps}(_m@A>ESFWJ8{(A(r2Kezi?hT_w zn{@d+FrVCUe8Zeg&Go_rlNBQGh5Z7a;5tDA_f04g$5k0@0O02yP(~*H5>dRc8Svo; zBz2o@fq_h|ChPgvr<`bnSV&4pDcng3CBIF$!lgo_!WHMGz(tzO zBa%6yAg{`SEEt5NA}$qV&Coec6~R4`9THC5Q3<4OQ8~|&5@$VuLJQPT^7a-Y6e9DG zqWio%roZFKi{XtP_*pn9EtAK@IRSl^xg9b8w(zuBnQd7tMcG?NbwqWBEk7w@7a6M5 z^E<2-VFQo702-#jy_mw6&*KBKFdABAUV`|8Xkuy1KIqWWk&IBE6mM!1Xfh$Q6OtXJ z?omRX%Ll<=Z`*etno}&~Bq$&GZY8s)sM;Tpf&My+`H`;b z8<4qkw_9>9sNnYQU;g$mYul6aO;y*Ao9Q*`9=NU{Fr=374Wb|mvHvF)TRco|dZ&smM0}Toi?nRY?#0`=ZLNA46r4k`v()YSQ(^gbO36>7hI*FTcy0ygY zZKc&ITb!9e_bJE})nWQ|#G)C{n-^`uX|bMhl!a@AW0$O)iD9tUym~BYgo!90#vmi6 zClb%Fl5Lpfz+rg(T^#IWx3QVnrb&x!^HX(oK_LoSKf1$hl%~Vnf;*-Q445cyc+$dY znds>J>2$5qLW&IiU6u4uRU|C?mNixB@Dx7(JId_GQfMJSHASc*qoQ^q%}#4|UU=u> zSs>Oe%@!#wvw#r^E6S@3j3(}jtxdwCNSy>ZcUy${=s~S1?gaf(p=s=g+QHK~mm^dp zm!!ofzuglkyU<3iQ7v@tpfzZY-_L}B|0Xl^@^kK#G8o1h3prVYP$G=UZ1C-j>U)H< z!S+5j+eoLfS2?|q#&a^MqQZf(SzN!wwL03YO!M$l{~%4W%t2{CnR=3$R+$;DN1e(t zsGt@X|8wg-lFm3zhJ4nv?PybGdmJ;LfqkUgIjR}0x^q{Fn!(7O0Uc$ANE~JXlE0NN zD>TxdKw60+d#kTX)HPdwB*>XK zll{UM1=Mh8kPf#ug730>^WTAr!v1B~^@XH_ZzA)Y?S?%zN8sk&Dq~Yo6~bH|>B-A_ za8k9vLNO+tpVR+-E_69Z#fpUzQ9LVy8UFMU%PNl8M|_-Gve)U=LjEr6sci92**UwQ z%lj33I7!Ls8_)Vd`0>J~Jj^K2b4$`Vq=-17l>iw2rMjkp*9S7>&5aG>b&=9JiUT+z zaUt?fqb;;JNP4h80t|Pqh_voPlbFvXQ?g;*^pFMQmbZV>*?m`Ok4C_fYUV7ilb^A? z#{#Ec;%N@oe(n+Oo@DP~#u3`12SirP8A>HLN0}!znX5M!xI{Kb<-3&S7RMRQ)uYDb z4Y`R?9V@s{eV1qZyjz7Mi_J5%=#c^qkuf9A(B4?xko4QqLR!BBr|jisES~hj*&W;*G_#;M1H#t@yZW2`3G2tTb3_>_02?&PvH>xLpGAlv<%$$om_ijnQ!ZLc zt)OD*;vQpn>$8beGpSfss%<<+-jBZ%2vN{8dRz7CKYzv@nntG8R<&{tp&8^%gSRVoMk=-{?89{G zZfr{8NOQI;-hozaOjLnFS~8-yW-8h}GOa3d-GePLkT3FUNg3r%M(%0Cv@6K@c-qXr zbG7wrEF9QGjq4Ov|*zX{6;D^C+LGah4a}O3mz?neIN_+kMXOIrb;FEj}^c%aR~o<7oGL_u|UF!Dh~Z?*i+9 zqg-Z25S9*PT3YZEU`c;n79&&&ii~UU2Mv+*bQSvj39Qwj>5!@Svw?MG+2|WS|!Bkp7oQqxm(q zoZ^Rz*hoj7%s@?qKR8CsYsvNd5}G(hOwn?8)*!5@nyab0TZu+O281Z`YT0ZH^YvUWxT}8zL9kQ1@}x!yzO3lwj{QXb(3mHm7i)zO$np^8k)gj@~=?&7i)W( zdq#2%Pe-6E39z7OQ#w-Z3U#^R0G2#SK|{XrGuNdLLyc!h3QK`!Tk4Y+?Nr4nAxc$7 ziJSaE<-Y&!m#Z4xdWN)qqce5;T$o0xZHz2X??6(;41+Y;RW{Wrl4ql)s9Kezt=q5k zn4JH)Uu~2@;sjp>NE<1#GxVcsjkp_@tB2vKCAM%4Xr*Ks`Qtjz-ixcx$aL^`jDe>QSX}u&PV4dT=kH16|n0E-1AL4DTfSU^*n%da3)(ZyPeX25~lg*iHOj-Z*2hqQx%PS0R@Ji8M4q(K&2vGA4?^@+kKc` zOGhbRcj|>%z3)zHByDH&v$=*{qV>Jp5IVTVGvj>IKG&hH}=1$|#(63`yy)R)JLP z$aVWi3hUd#y&^eg07T}w5YHw=E-b_yaYCk9eI#ULE0+qo{(q~+>}2Uws#SkCmj3b; zIb=%qQh#HQO`)Obp|1*{YEQQ$J`N?O6muZO9F)ig3YXnOC{YXrsJuL@7~W@pzRKi8 z7OpQX+To>l*y~<(dA7}@9e(Jfef_QXz1~%8WyuU}J$>j(6M_6n7pe3@H)l;|h3Y%{ zjty{n2tLQyjV{yyAOG9PV4|Z>4$N`?k4+8+=k<1)>A^4D!aBCH5U{B1i6;P183%GP zSYi!I9FXpJcO=IwZZ(OK@Vv2QX&;j(;ENmh(aX_)U1}|aFCfbNdOqO(%_mle2QMaw zu-U!kcYT)Q;;Fcv%_YodEXuFz@R7vAO5sAZ$d?BkgA|SVWP^1T#dQ_UWffJ8ext^c zlJ4@x!ty_bBN93!T02QAE6J8nF~+5XzXL^!2sE}Izy^;cLU_^Ds#U zwowzf9o$&^=el^*;^!UF=iX64lG5(bH_pKY4v%y!k|}r#WCVc0Z`C836!NBS=tY{7 zO3IVpFp1|=8VkAhdUyh<;W>rL5DcZ;<(SDLk;M0yXrROA0u+^GscwbZxD>ab9^{M8 z7b9R(VMBob!h%t@u5Iz+VaLy zg^Frmo`y>*LAgLby_9NMjVxJar^0w&V~c2E@e*KBL`k*@(z*0YO+#$(neBe$#oqa4 zB(4WJ+e)-p^E`CW*~K1Ot$__T;)94XPyt5xE$$~ZWsGz$7Xyo53I>VPX40wR8U;$f ziay)ll)*G0ap}~S)s%oDPhy>_-{}+_9r?e~%+8R^_R&sOd}Zcr4JJxlWtupeP>b=l zq8ddmtndZ6N=!YakQ4+GJ1d=-pJ>V^i0h_FL23~wmo{Qjvs9J4i5`B2E*~L|%p4pa zl*rE)+Xyg(8|WSmHYa^GVA&K=qD^#f7a0(MK5~RpxRR2iG;brt&q+m`NLsKBZ9G68 zwKR7n1Cn4n!yyJ7R(zB}nq3_C8=1F}`=B@NOVO0TTZ_;K<>QE^&W!)@RC^i&l711| zb3%ZU3yD$;SbhR=>*UTzHG?Srkr952D%TtnXJ~M;mr9IMiJ_d2u=wZc#@qF|=avxS z>5u%y=k_^JFb0Fp@ApfLT~Lfb86_Lvr-(}6KboITUZfl zDm-s=t{4io;XW*WJep0Ca3zLVHvW+%atf{cpBi1bUQw)ie#CYcYAx+~oojg;S$R3Q zEPnYhP3hC1khV&uN(5qR&O(u2@MT^kBuqn{o+%|b-V(4;3I0ISE8a%&L@hB%6Tu_{Yjvb7;mPIlgIc%9Y7O$v6`h3fERhDEs2w+@ zOUP4fUJtyID@t-DOE{^O*9t=t2qf3`q}KS0pO+L|n5jkONaBn^J(KKex{ZyGV%z|~4D+PWlYizOhR-n~CFJ(?syx z&Od<{eHnLOP1sQ=tcAZSHzJql^CkE>`X7;7+F$jqC3`z6AeSQ*`C6^LDK|b*+FZ#5 zOkc-yw+Oyod_>H@i4-`84>0D+vG~XE<>+*wr+O_MhQj%*aUj^M#wa1dV@d2pcPSOr z&ol#sjWI9lNn(;vWr#t9CpnIX?+beipw~t<1%cLMXG%7{pl&SOKG4Y}5H4<}l9&z( z;1RRLPhZ6t%1NVL>&1y~9L2PzBA%mYgyvmL_TyGRl%Z@kZ%%xt75c%eJ*V42j->5K z{VBzmt)rc?8rS*OF*()nk*{BI(n17hTyFJe?f}|6ue60*1bLnnrNms^Nzh}24-kcj zEL0?_ia%^vC9G&O`F@BL#M-?;+C0eLJV@WXf)z#W6dM+$S5QGRnwgBD^v}c;Efoq= z$y7nr5}Sc?{RVRVFC?D)Qeh}Z;WOP|Wa_`@V=P=m^$BNE4iM!&cRv$@5GR8@GGVYX zU=HsP=$H`cn7%2KB=@#sX_?5gv(lBcb zEygb_`NiYwzpa1{&Rqv-ZOTpfkWa%S7Ua{qeHr@V*W6D(rl3Ub4m z17PILp2^|$F;53^M9(K;TQVG<(Xwx$E<=mLwgDjQL7H5Rq>eRGB`l(%*%^?mqZX)x zv0_JIbay1dx1#;C=p=R(gleswt)kmjndy4}%0>Ql zh$ME12&A^?G$un$f1H2Cn0J;@j>a1R^ogi`BeuJrf+vc@6yM(ORAS)C)zBwxHyFf$ zkxI|%Y*_;i1lQVtL`YBvP@+uOFvB1`UY>^z7tJvI|5CPmSM<&@cxntVyth&snBNO4 zCy$-s;-^0p3wZXi{y7EdV8xwivbV!*X-JN9*a^@^F3y<4R1tN?;Km4ZnqPO2w{-sn zKSU+Ch(m7mn^_5oVvYJNf~G$N?XrTc5FBqn?jS}j(v?ihzdx}7&y1KudY9AhOz^AW zQl$Q8hat&&g6#SZ61d_BEAqS`k<}x}wjfBhAW60afaddr{H%@={AmQHxH4bMvV;UG z%LG8a@4XC2(WzEMu}BtT$L-svkH;K6R=0>G9T;9tGGaBTs*_Uh#pk(+3I`6B(K2 zW8&xN1;JwW1PB>o(j!_D30*6--#XVI2@WociNw$f}<|(MA#s!DwH~|~HTa&Cy3#?0n zq+z4{!-Mok|Ge)_S}egE=`z(xB4Q%(0lrnQ)Hb#9HuGMg$sp7yF{oRF>%G&S$S;0g zuY>6%jvmtsuO7Z@h*orlM|6hbpsY!iqtI)qkki)VbTwqN5q`c2d48x|ZsptgEZ!0^ z=O3=b2Ss4AYiq3>SJGx9F|96360luu)OBLV=6h$YHZ*N&f{@YSS@KTd1j#{_*eJWq z0r5qcTu7epB*AgWo84GI?mz!pD@kUWH(eMa+uR%GL#C>ba@|y-TB`Pp*@<{@_}2X4 z4^OT&sO1t~dB>KEV*54m1es=}BbYZ$ClU&T&>xj{t6|&!qFZf3aTX9|CV8@jstDNQM$K;3@PYDfFev^rg(Vq|61zjuPyn zLJeq4Pf<#>U=&OD<|z`=Z4I*sFjMSMV9JZ1mAFIAc|vztC#Yjax#^Or_$J8tlE>Nk zqQ~ij(!E7Fl*kz4M}HSp;E!TNP2VP^ySv1>BdOJD3NW{I8aw+M-~HTP@#$&x>3I$c z*{G@tYd#x(JS#&MwJS1@9T&)wV|Ii;(hOpvuVmpL_%kD_i!0B+g7~%v$0aYPBH=2+ z8>g$aEv>o?skXq5u}DKhQ9Q^?v(B3}N=p+>#Zq0_v~Ryp0d}TXYvQ46zVaqyqPnUq zNlD0lLP+L{mSjaw%o3QtG;Im=Oz!aJXeFb`IQyuGv;G9dUs2qoc$GaUL=(paFXZ9} zAp|QXrZe2>k$joO-3!@U7!{#0AEQ0(-!Om|vM{pvZ6qNp{8hjt`UVz_Ei&rJ`an{; z++~m~KH~-L?nJZ~kKS^i)x5RnL>eeh7i_bGlV*aE@jA%6HAp|c!o4xe{9IV`>5JFn zz0~bq<8!U~D%3*Xd9CTO?YHNO$nrGD`qT-Z>3NprxyAGlP@Cx_`?s?GE=;JoWL zx)LdU8^msh*LptFdOp>9-EIzoyjp?YYJhLIzytLP92AOFbckgj4F)QO%OoTM8RxzVr8Pr}k!)Zn`hghG$r zZ7hwk9)?16r(?BLife-5} zZr~$j*%(mP6G?L9IX2AU0dS*|XgMKEJ0Qon2SIvp!w#Z><5SsM-k-L&afxGq{12<& z&{lDN*HZmH5Dil@<|8*e`+;+LdU?Eyckmr2*s&>N17m(3!l**-j;ZEsy7p{3kZH=& z73H-1ID`=N5vu>;7c$O^EasIgWPO9XaKw``%a|VqUjoPu;SIFeS;x@f+7p49Ia$|Up&%YQA1e*MaT zi{FXF&*L(5@;C0*D0f7nHVePY&g&rSbhkSG_90<+i<=dEwlV@H&#f zmqa{;ICL%i`6e!}0niP5av7P>hm3f5U3Pw}t@C4G!=p+5x%#fV9y;NR`2eMF5Mkko^_+o%R%S&=$#Z05 zevyS>8SK7*To6!r*Sl8A!HF^J88Ua|;ZNKKlc2|tM_uy=VU7}p*9|ZCTQI-q=)iz4 zHqxUFUhmJZ3_l1v2eqD~0Eys;>0isTaeA!WegpS|-&m`X+Y?@>PbdJV*$UGe^<0RX z&3q%LAU#^i^Sq`dU!BXZZrBf(jCfr7%r4#57hao#mtm0|wV7XE3~a6{N8Y!G1b5aI z_^ve*X4b#!yZ`+dysHhxcA1%b>rQ=wve^#j@Pl=OfOY#2ZT5q0?tX3VerEf73uw7z z{(H;u_o0x54Cre*GBLV^!V-oLlB>Y4gp?(wq?%peo{bqNj~LI<_}hjEz|i2S_u?iBQrQiw0Ud#f0> z6jGA*Mv2*9?D9=+IFSHka?wdz1MUv^emRKKy65n$%*7_#{0-Il8)}2fm|j4cL#GRw z-wM6N&hdHZ|8e_zUKfwYY1bbDf8F)86;9+A5t&mipZof9obUgzr~xLke-j@t$vFWp z&{#}mfs+LVXY%-UJfGhK^knVjvNq;!+2}A-T&d8S@5V_&U}Q<1M|-7R?uM`oV^EKZ zZ4~IPzV!F1*j*_>Hr+e1e6yq||1*B|TORt4FQO*CB9|(Kp`56EAV%q4mv^f|MUP6r zQIo`BqnK%n_(9_yD_;jax`A_`s>^tCn&NZGjnGT8QX(g=mgJGAXer^l%t`uF46PgT zOcT6hAmhy}!%kY|xf;~E%oBa1U1m;~k;`jVA9Zdxr7K}xD{$wz)O+?{^i!PmHh+=t z@l7aic%vQBLZ@rO8=r%|{ikP_@3Gw#uebBH)+WD&i@%`n{?q)jdwzTO`9V|eY-BZW z+_}(tyxuA-L05h1d>Uzb;Z!)IEzhsUTP6U-Z|5WxKar=?e>~)1xJ6=zd^+-IOc!O=Pz1PQiFW#9g2onEgA2@Tz6)(6T!x39b zS5Bh&RgZ(Y*I?}B%buHcfhl(Hna^g8WXt%XC6Hg#u}KOoy#ye$CL?e1jw?Kwl{oHJQ!UkUAf8cNcd#|N zPIkXQ(dXFmz1nJ4;p8OfX#dzD&vCpIpubwkI)Aj<>#t;cw6PbGN7mc$IN2*3_Bl;OFuZ`+Q!Mpsd5oZ?p2cdc>dy&3D;5-xf}hlXOhHHftbV)Sj&CG5;Nj zitDCd#PY@S(P#hLVQ%RDp4e5JxIZ;A?N!D=71bh}W6$q4=Y8QYzmhjPD*u%D%_Z4q zZHukG>t$4ZW)!*I>^I7$9}@RQpe+7X7S{%=Yp2DL$M$4odfU9ObNSb!X_P`r(N_gs z53N?52vf_`@rm)N*|p2WrjEqe5fff}XG(vW7Db(F$&mn$rwA9-JAhwQuX6&X0Cnbl zZh-O+DVVT5daNN^xNJ%!x#}+>!lqn#ZUTuvk1()zwx0ggr2mTz|JU@Do00MlU%k`* zL6m|Bi4`)vUczG5>#*SaLlav6No%Ajri!9Awge`X4l>vb!nTYnkE;sp?Cq3|LEViWazHAKnh^?lGf6yyhn%j6F?`5KrOIJNs^sB@m zFj^I)ddZ5#t(f04g5&B$j`WIw01C4!EE_|j0*gJ!fV_EM7wO}^f6*-{R$D9n;uhOh zxn1Qhk2#%4?|yr8SNquR1oK;-_x*9C*v&*sYi^p(=Y@AVD0$mXJD?+|V-5nY7RS%k zZ*S8=xZVnN+s@XTc`7#kf^BY3W7}@InhodA_Pp_RtB$|f8{bc8EY}lLb>jc5c$soH z9^TZ`OQbo{PP7o}we3Gw<(4ml{M;@D7E7Zu;oDpG)yuu2XkimfJzr6&$adVCedgl*l0QMF*G_n3?;)sq}%>73#1ULP@0#0|aw)M3){n5SGHfKh`CTO4Xb=xf5PUFT(*W;TW2=x}cOKL1cH5j&7+Fd42 zfVL(@yzzy!?vXB6nYvvTPL~3vUhjcF03t3SNOYzwjkBzct!9=|u5XE0 ziv*N8Ec!~zo9nS!~R_JHxE-X znhuY?)}lF)m!GY@`hU(F1 z+&?P;f|blaOQ}(%ZIR{e;ivZS=OA6k9dSyN?D5Dq@A1XaXwR?=jxh5~4%1B!@ZF9h z!>2{gS(lN({TGkN<62&Fx*H*P&qHq}{hNaQmb=q@cQW2nP5=kUPuJw>pKC{4?YgJw zW!ylItsr#Gme&{UCbQ4+sW8rycsBi7pK4O0(vzsveAh%Sob&p z+Ivq!6hw1gvx+SC4Cd5n|n3_c*$#`EuDVP^wVwBpG84jM$r;vn0t1- z4a=0__~BId@tzO2686Lo@ z5t$Jv<6^#_ZokASH$e+Y+YaU_dv1ZC^cpK0KwP?fH(QL;n&A9wHHDIY-8atBHaSAC z`X)%f3HRRldwynub4LH4=X6xfEZ9ary(V8myK#HoqkY(#%_h_*oA+x`+#bfIl?I#^ zrvd$<*tay>jTWD~53KB`x(z48!?fV)W`2Ie2#KJBMH7`ja`Ob^t*iJy8+Q#Q-m{iq$T9=c{8?3n)EAj00QN}Dx^L2g# zg^pp9b-CNbNohv%ysYr(A^f;@OVIgcx>Ba4VE+D&1+YrnQs~U%UT~*z{VQwvN?3dO zTCer?%iNMLoL;9?slSxMXMG;TVyccPPYY6{9fn@l`^g!B{_+)$UWbj#W!~+>Tf8e# z)+R^2pW)FL1yq6J8Vxe*rxRZUdD@X3r@e$ZuP&A(^q3?ET$WV@w8q|Y8wN){+%3yZd>F3V=DkR|KHA|iby!`d|Pbpd$8aoBd5`19RO*9(Vw z5^TZ>v6~Xhmt3uGZy(#umj(@H+hN@cgy9Z_~~2j_4LMx>Wa%$6;eD+nz6#OHsn$!_|6m!rmeT(jO{IbV3lD_^_nEWf`a_FVET zI^{xdeds;?XUo@o@oJvdEl<1cd@`#``v%BC*wOql_$>%vGRqz-f~|4M)8sPW*H-O5 zsoi`VE_QA{sq?;=b7%nSyokO}4Mu*J_Q`dA@S+fp7{-#dtz*f1xJ(={Fx zTHtyeFbX^hI8K=x|@ArHcZWVM{dB}%O zwD{+pRWXZ~1HtPD%lEf4Z~2ewl&r6jkUM!4wto$t|x?mSZ{3mjh>3Pow=#68g_X4J@!r$vwL}w zxrI#~p*BoakNQfh5K`n0l4wRzD}=A+lyM~oO~>^u1<8Ny_M-O0uyDLE)0D6hG(#xB z3&L8SAp*@$kRtYY+8aKWUi*2>ihg1WpHW*PRTHyQUs1J=)gxT4F{GAhtExU9Q2ar4 zpRaX2@0a%W-7iP$_C2xR=iIk_pMt?sWMFLw!IuLJwxs{$zbq+-WW6kDV3Yyc(o8go zAVCC`KZ^FMB&P*i6{5;g+doMX$^QGy9K!kfbW6n1L$>ghj2#-C9hMx?8bMyYw&0-54>Mz7AsrGu8x)D#E7$W3 zyZsEC-wJ!(>Q$G)6F;im0!I>m;$<&Amr}Nagmh2#@OttKxj3Z+U#Jqi9zJif!lF+V z&l%J@gt-P=menp+q;p!;J(X$m`gK}&)9+*>t&5V)jS!Mk!)~R`XJFb4mp83;z5BVP zX10i3=lh?nPQ%5r7h2AbcH@D%3C>BqvfGLJ2j{du*LA6$N&#TpKx*+}Q zUb&dTv^MDQ5Bcn}v${`@;ibYv^Q2anP2g}~>3ZD2;;(_d;bI=VINdD=RCX`6yF$lg zHiO!acYJ|mh-j8J&4_K1iK+k_Ra63 zoYn8$Wmvb!{%xLe8w4C{8CZ%j7>(?Hb3J?Nkz~AnSFY#Br?^ML?!h00AQ&`-~&YWfDcbLiZklF9ggK`M@=0|cw ztUX}cc3IQoa@t((FAhy++a^Y43A?<&LAM972a8N>^E0q5xe^@6ufS$S zEJuYTRTD8Q&{6Dr+5G70<3yXoAfy4a*&aYArKYd-0QS@VpTP8<&c`*I&*u@rSpal? zO42=e%JlPulm&}A^t91xzE|bBT<8py`L(4*!1DL08$7KuJUv#5)=G-T(jQs+7qd=; zah*t-wSs=>iZ02rxT5j6A{zZ6HGv; z7JUaFdj}u+fE;;?99Gm-@Dq575oNIdPJ$lUkKsFjo`3_t@%}5f3-Us*%Qk1D24C0l zhH?q{Nd3_qYIJ&1`VYiB3QZq|js&f@hK_}TH>Ux1zTx%GNxX8 zBvAb-6~PqY-`05Tplqb+*;Qi_MM?Y=Rixzf5Sk$>=e8m~SR|ZaWQ09Shj$0kF;hBZ zqQ%X_cwnMGtVOVm0JItSK1N@_Ilb10Rp0jwoKLu=%c-+rxnXDF?rov`1z%T*!$+?Z za>FNxAFAIcs2DV`A5@(5%S2^hZ?1oDo)n#h1f7KxgQXbVQ;fn?l%hmpuskva_ecKs z)C9uZlpo1CFk+NuqU2>_L*?Rw6yai&A)UW!be4Y!=UD)Q7=1bg{v$w#wglPHpWodPo7VntDkp5 zXh0mlo3M_e!IQDk9zS2F&2F#C@~*1X&Kr+h*IeAtTV2ot%tqderG8uC?5N-)ZK2|3 zGDl8BR&9Hw?4k-ts+cl%rt6_Yq7$OQtKDH68#Nwstqo%w&B6McY=1qX=55UC{* z@-fMLk8|BAVrY*;)2tocS`59%feSN{eHLGaT%!rvmN)M(w-TL zwfDQEO+iMA{1q+>+4?C}1Fp#SUP6Or88S=U&;9LR8-_u7}wZ!Ua)RLh|@v4ic($#5?Y|Q;``L$f;$F0S-ABPDC-RFEiyXAXtmu9CQXVq}4Fl`HgK1}6%7e=kkMhMDq z&)Y5UwLi&5J@rA_)a!59E95IQ_X$7H!vxW>FE>V3yn+|4;HTa6{f`Et@ELOu-{rbi zzV93BlB39&!uIDc4!^tka)WoK!@D0u^6$W|v3ZJ4!NW^;L0rMp;1=+EmP3_q*PE3M z$L~SEW~>ePMO=5SwZslTKLkG?i9TFZr2sLfsl{l%V;QC- zv9*-^2tnUs9a8^)d0QKh_A&XGXjtAyLDN6zi{`a?%nnmO&ka5vwm;vuKkv&0150kC z0GrS)_h2y!UY=aV5&!d=mRUoDyrMFN#Hdh1%x+4MVtY_}L@!<`BXTHbRGt^zjW|Fh z9zybeFPvO5v=5~WM!KZ}C2Vz#o>vHAO6-grbl(4QrdSX``!$i4Zd^64Fkgm_scUF4 zi~avYuY+B(a?-~`oqwqvbtpBTN?^GV&DopgbDozH<2)nIR%AH81NL2vf6EyP)Ee?~9iRE*a zR@8@?N9`*A4~cOn649#Ymp@t-rbP6Mra!Sb*mW|lH90nTSe*duXe9wq z9_$JwI+jKY{SsHN9TJ%B2d4X3{_A~~A`%-RN4Qnc=4r9)org0@AwtSh$A)$k`6Xk$ zmTt?(rad_V9HZ+6KbcO8DfZfAx=Kz|s1m<;Ce6`&P1 zS*?OE0pU(wc(|Fc=|L`I7am9KgevI9YBHHCK=s6+X!9PQy!>n%Fm=XU!;{vq4VBlh= zEE-F8d*jp%r^PLAd3cL5N4c+{IodZti8CuEZQ}fosTK$@4)m;U#?;_6ilg$cypitc ziO*--!{;#AeV7}LE>!~k)Ptzhu>qBe+^xRIrkwz=U71H!tf`+W- z(x>G*a1?4$be`D(1RCv1R*{O5tIKi0fBbeyM$+--EEG(p?rx%ORfZ=z{%xHS5A0Hn$D*o47{IV$$9T^q0((HUO z%5DhJlf1cZH$OM#qR)5#)V35Z>MEis6&3awOY85n2g{d^RDiBsFW^?|F|16Z>lfX#|X(K3yo%Pj0L z2Yl~@rXit>G3zq>vU6LXV%*3e%ZBj9w+S3$l*5n_i;HRrBmYd~x#L=4&wo+#(7K~p z9;UGsOdVE~dMhij{mTa5#OW&MJ)-^(IQpO0SfgjciP_uqgeQkCP-X1HI}~S*WM11| zAPcTuKzSRM(t!!{{pt4QKl~%WHV}dt?28*?_fnrc^qh4aX`y4{@NT7jRa6N@s~$_D zt=44*sJ55uR<;G(5g{h{|0^R0I;NlE>Go>|t1CZrW(R3|Dr@deTO)~Lf3I71w;Q@} zHJiWvk0~mJh!mmJiQ83FNJ>+lr$PYEx4kKBu)qQ@SxDy{SB{sw!`p<5B z@ZJD18}~%!haag%r>RCi)SiEzo_vg~U&nHZ-(?p^z=;Dc7iZYx71vK3{!Blb{Rj9I z`Hq8He5YYgTVsVR&wwnyw;1#zZ!4>$kok_ZJN$Lx-KRJCh|h0=#YA9dOgnhH-s%KG z0mlbdWfnho2GO<{so10fx?aZUJI=#@zvQg(o2J(KK7J+~v}9tSRYC4RGphm^N=I)9(V+_>gRAAi)s<5&X9v!46ZGx+5}u7cq}SmX&ye9xmEp`xh?SsR;7KH=U0Nvg?p(GJ(RP7 z11$aE@|xxPDSphbt*N|-laVk}`K7;eiga@bQ)2~Rqc_?p1xx2Y@7z@18-O!JdpT~M zHJ~g5)70o5@6bEn&>HkzI5k#p;8uLbV8P7zzj9pvj$<^69036TGgV(`5i?Um1gC)i z0Ni-T?8Y4!Mp7u)G%2xKu3id=5UULuJ{sl5y zAmWj;owYUCqg2<{GSJcvWM?z2v-+0if~BW(b2m3T+!gZpA~n_^is8j-;FXiq(P9Ws zk9*`kgN2Rul(e}t|3Aan2dOB=tF2DuscpiQxtrWktRCMAjqd5u#D$e3j9i$=Bf-Xa zn9&!6;S4=LtS#l;M==N!Y<@y-9x08>w zy0x3Ixu2DtqnWT)tSJ|cSoSZH@{+y8zKXZ+W7zH7z$aRXr|2!bubrhL@&R-=6W^Z# zQRe)^N_&tm(ZiaT?+y)ILPdBtdnt^m^|25uh{XZOTFb9&4OKdd5-5Eq_C4=mPYe0H z?#S1b{x>^;nVFfz#iUy*M1+KS2?+si(;$#fqi4|}#$~=G3<06IjCQiLM^an_XH|?e zsTLf(bjkfBV38dEQcz~#MeQ{7+YF>MaQlsJPX+1Ph1An#rEOsg(mD#zoE{4}NK&Wi zZEW|1rg>m|t5kRT*bQ)kOJ@zy6OCUkcr?dR^Zpq-jZ{S}&g|D!TSM7UB{Li0UA#G? zEWNHQt)s$~v{Zp#Jm{)iA?U2o%G;x--Gxo)Z6}sq=Yp8}so$j87Tnu{IZbNAn2?)w z$8Tmx{1tj`Aoe! z_Z4wEf1!&U$V27{?UJ4z3OE*`2SYdRhPFHAizr2PJa}uFuymQq<1s!>?vB;v%wTsn zbcOJ(4hXle6Mi^dw4v@&ox}b*E!d^mR;_lH>EteaJ6iATK$$>j#q@2I#!GtDXki1= zIuaoAV9T$imK(%nf4`q-gLir2m!`f1Tl%ZimVIio>Y@_6WzSKeIY>ux_h*mNDJ!EJ z8rDwfY(4d+-ZUkqCWC=!8(UWcnUjQfesw<5#6L~sB9`mF*OMr}tM&h21M3cq-RG+LfXRfV`p0+^8{IS0{f>XKYooSqL*tZ?S=b zTo}%-FcBOEQ1z@@R!Su@j-$8jb?k4>C+(f+*UT4U!<40#m+!INeA@yaQ&g@Rsm7`c z=DnSB*f8Y)XWgd3lfKubyg%d97c}~eFvYf~hn?V53r8{4F!;Uf+pXA*;ck9*2u10$ zg?GbW0wL0{)_PX0sSaG8kTg~fII>|wpYWo+KYkyHrMi)uqv@4(%z zXqD=}hD|74lW7jkiVy)Jr!D4l|J@)g+Y z#^=_NDr6jXsr#$p*rmUrRMxsxw>;C*n-o0Jo?*H?kfXGSZly{nN6!pS`{y>KD&II` zhyq-9e>#2y4OOexZ8mzYPwRQ3;PZLy9dJ(}rq}5%E-rSsKXn&&g9$^Cp_Oe@7&5#v zHY0^2u|>9Q4Mlp2dezdj4>L;g2W#m0CW2}AFj|HVH6)BD2N!>>Z6F>7Ek$$`?Bvpa zf}_UpkPu?b)fy4KtZ*(DeT$lhPO!!@Dh>~^+Kk;YgX;rujWJEm0s))C7TBR0eovdVRq(gN$5Cb!CCrJ_2sfN){08LzcXKmffnPm$7b-d=r({ zGnK!;$`*oI8cG^*nqiqR`bPgb9A+hb6CDLVx$>WeE*p~S;InL;Ay?&8AvZ2mvDn>X zG1y+rWx@=Xz$~B^PjFsR;?!KBLjQ@~Xq?J`hB=<7zAAu}0u1&t@lePJc2Jo^q-qL% zV{UgD$O~((-56IF?p;&VCt*2=1n#^`^BeU$g(;`gwYU()C;c*_% zhIVxmBp9c?)ILl-^btOnN^m3gO%p{o7kwTwGktdA>|oFkr8Jnj|8)vWl4ocV}gLO8IL{6h*H} zPNr0jYbg%FWcT~0M#4MItNZ+NM6rOmwrBT9V5#|coT&fGp@(i$aeE<6O_jc)xcaz> zb35~A=HCORzLVSrnc;W?*NLO&-($aXQG)xHw0c%F^V&X(ON^V~yM>i6rKI%YpK!)+;6iXs zN0gbVv$!&YT|9;xk|X#m8T;{nT&Ate?qpR~Xspx-My)Q{CxAk!UPp1ryQ>x*72xq$ z1b|zH9XD(JPTB^>)h+&aDdCo-r-+892&LKtoS`b;PJ%>y3j6qRhw8ZTqWl5fc)*FR zdp+m&17}xby)X6FOX+fo>Nx#R7ZP|T^(ezAKp$Ib#l@J>SL5%f|5smpOjK+njKqQq zYOl&k*M^{D)Y;tNaj9b-nMZDRn0ZFq5{9m<{nd=x2=nxv3xN`+CTSlZPgo36_cKCL z@~`#;X`iW!r#}|;^ZqM_J9S$t>vOtVYld11n!dMKZ*h(tc$}Kw7w8LX+$^cD-A6cA z)yms8A94_MG?}BG1>7-WT|DoP3y32>xV+yd>*@GNd>QwbJHG#y2KUs974Syat zy$Q_@+3ild-xU@&>R_IaRhO2ByJ8hIHC;c{zOGJm`GH$Edh9kt?f5WqMU=|SJn=VJ z0;dhjnFjwob~n|1Q)^O;wR^i z$#-MOZh@;R7Km>n%SQze%}0{G{HJ3-s_89o2Z84qN*C$XPh4NZ|B>BTr6I_C3-9+j$uy*!rFSJGodOsj9&M8>l zUKqCW|2xn+66Q0*h%u4!JBpzqA!byg-D;a8)IL19T7`*!s!OOM;5kV8U@w*1O?iJC zb>558;tQJ1mId@<`JsEqS$$t};Ys0Gc1@~f1`{Mr&=0b+er;;u`r1PCwXCMQy{4$- zYrSv6B3O_eZ;x|~!_e~EXn5-j!@tK)R3Bw0)#Rx=N>EeKt=rMS5!H^*2?s2}zjp?$ z@dwS>3wCK{A;zO_P#Bbus0(W|bhtdIJjff`DLJZ*OmG zEa}k}(uKkEa(&~qxA?q_{n}s}8LPqr77WOp9!tVOYr;YEJH0mSCA+G8u-kkuD=Pg4 zTx0%Zx5=*!kvS(Y{NYKTiJO(OftjAAyflt15X_m2cB~U9|GtTGt)FTx4Z#^BLnd=R zWy-@L7+}Vl=(I~X2MSv0V(yffil@5^d6O8K*;kLeq;# z-y@0_m<|1z+7j}7Ge4v-2?FgPQaRTRyWXiS`um0BmcrKa)ee*M*tet7pSUUllVac+8X>~|6O)su+svhvTN~7ru%$3kTfsbTXu}SUe&sIpCyIg`N6BX- z47ZbaKHh_Lh{nHfE>3RLFfGn4#l@XcyE}xQ+=v2R%XQc4%wKQq2cpAbmdS_(fX5jVHW4IYxNB8WQ^Pe2oaiu`K+)vzVJa> zW;dC6Gf|!4FWXd$5eGkFC*~WBR6RG*fQ&*_f(KqJ)&7T;XLUbizaR|4h*cX z|8Sf>_M#f%9%moP3c8mLG+H7z*Aq;4B2pOkulV);tYN1MuI+0lQXgU}PS9K?%D=q( z@f-q_)mDBJ+g3&zIL1?0ChD5_##ExCtUqD$AUXQhi+$pned4!3Rde0du^pL-LbOL^ zKzl^GF24f5k@zx9$n?$XMszK_^j91+X9S6`MUz67f#Nbupv1cb3vrH(Od&!((tI#o z2U?kdZY2nAqTw3GtJJoCsBhXi=i4|lOA2=WGsp=DTFB7l_qr_9e%xjH#$@Zqp8J1~ zaK!Gk4Anl@L68QSRGsr7BAb;5?EAT(S?Dcc@Lg6+x}NzmC3Z@ES8`p~m{4`o$^R*u z;X)h`;lL`i!Zl{sLlR}2`AvM`0B>nuck_c!nx$vkkRu=3Ix<0fG06`Gthkl!X4ijU z3FNqkcGBKan!wGlkEhTALxp*aj@=yxl_QS)I8;tGRHB{;L_Ja60rj*C`v}u~@He&< zQ?o_--ju25!1Ch@dH@`fZ2P&sK0Z}&TaL5BJY$LaNJSP5*Ne=wSc|xu6U~pf+hJkF zVB-5i>k9+I?eAaFTDPgE4R_v2M>U;OKMu`^=4-?%$q)pwLJvnl#a-Y}=~r&$$G@d5 z0-}Y2Un#9h8T}J&K!QGLu$`+P{_wL_O2)N}fz8^ygHX>v=~pY5X?^&1>l~iz8Hxi@ zn)G=)g;O$%@7k)f@x^mhuIVBZ-)89M?^S9D>HOH-<&i68cGtV98V1?_z?W9zg+zj= zL}271FJb~CiXYwgB1YJIu|duap&aR0QY-~u@2Oq9+&EWT{<1+}Y?c+} z^Ro@uH2I*v*H?`;^*$_519A%2+DuuJFc%twjqnms#d!BNvhVR9-hA^@xspSm6yBt= zxu3g2lJ@BqgaWdeFnl1%aZKpRw^nGm`dzS&3JWCeyNpKkt74iUK$IvsqD~=1p33AJ+AxB`q0!!}m8g&nSINCXJMOug8lv7Zi&izkMi@t3d2V}UkePj<2{_2`>{AGS{M1klIS)zHhwmH z&VqB!+?a6<_wTc@WYl~>_!Pd?a8*8YRS}9+KKuU~K!u{%_Fpn8jvJ{O3rEp~ zppknzE&#TV)IWn*=<7>R%ThI}-(|XU_ipDbB5I9O6&Utd?JDFpfH zR*MH2FgqNuI{X!YksVVq=AOGxbS$mnN)<;#bvscAoj6#lY1M}k2$MNEt8VV>?68Z$ z8}bODVWl}aInrPFZB+x{vLhh2!-$t17dsyEPMV_shb~+Be%Ft8X2^`9hvXc!6X^2j z)GjVA0$YcoULF>n#U57VIMs6Jdwa;$$5#!>ixH$jxz)7-h(f!4V@)GUrQ3whs9uLkzv-eA!RZTF{#|BDNI_lTeR!b(G zv~By-Jm@~ZtU-U9^x5a<=OFegFXumEAI8yJ3L6<@uFoezZoF5z==%<$Wq~j_bd1|r zRX;w_=lj#*m%Q9oif9C#net;v=z-50E<7tz%6cjNd|8%WRI=N01Qt>`)=+gg1O#c& zPX`a7g-`~8KVi#>?^K>}(*5QU-zP({xwirkB^KvAwR-v|AsN&^dPuBqtHI6R%~D=rEUOXC*`^_BCkZtY;=Ckw zj)(2H`u)BA@sxq54$bPDSGN!ZOrH1<9I*l&Wvv4Xk(fNM5&~YS7cVwBG3B__`^i}p z5;JI06bqn%6-wGvO(XvO_1RDC=!(W#4u}N>TKm5F&@_+S?Urm66(+BsUdSlo^_+I)yzJe5H4`^ z5GpIf(a8O(#9J3!y*$(8VcK~ADOl{zZhxX)G}ZvIsn)0zZWURT@lcy%JHg*=5pf*-6s{TkSa84PZ&HLZ$ca$ zpPy53HLV?&?ky+g=G87cz$w$q9yZh;CDRuvEk_(FbA%sZe@s~IaQL{wsov5o%k^xg z#PhaYZqP|yq>Oy@OT$O)P!SlRcmtOS=D3E07~dzo(T&8BTXlJo1ABKdYXaXS*-q6P z?JgOy4(Zi?aro7lcAFS6Aa8x&O1DYJ)8D84%lfN-B9n0rVN3*+ZYSH+%UYr$A_2a) zKJv<%n3zaPN@{2%gA7P!=F-{WniPnvoTSbAiw)=VEo5m$2`XBXD}6p0#mC0~@436^X((&-9s4hglgrSraPNybjtOT@G@jb9;L`KAxP&xPuXR zr2&hyz24DZT~TlNWHC0Qe_*VrIxSk~a1ef^iCYQLC9i1Zv_gk8FP0-%gz>W=x)mk^ z;1r{f@jPNOQNPzyF4k`&_nDa3K0n)k3AC02WBAtllrVM)@aC6Z`|FBSwCZ#JAcl!~ zT+-=?rE^}=Z?tMqxa^zDPj&rh{v5Q%ir3Y~@b3 zlA3%xtG?<7X*H#S;M0ryx^nkn>@W2&U|oMS9<3b0P6dz&%h?#EfBd^kJOs7%qaji{ zKO$&_2YYyvE2tfwhO_pn^mrf*5z4X6U{Vr!7C5;M?5YjeI^t!jy4X@` z6>AnYPB)lC7JHtY%YHZ6ezy(Qv_(f@Vc}N=goM>P4bFFL^VP**MZh2HOIZlq#U_k( zx*^U@G`+m+G?sg9v3sAe_;z^bk2jp1b0n>Nb*M1h^*+dJWt(Zqd69?o-+4cMR4kzC zw^r@0=3?Y$qFpMzbX{6Aq}Js*nesfEPAC|}LUpk%Ppe&!k}O9QlE8kc(R&T;#|+Xx z{9ImVYrntyR$2N%nx*O=yb)^YoN-f;4S>NOeO+de)AW1sK3BcELqIWR^yn8qVLIyw zo_v?Q9lq|D}GM5pjnSJAUY89SSXcf8mnD4FE1GL=al zx*B23#t#w|I=d3|jf3efGk=q?n`BxIwlwo`WC?*hHdOK5@Eh8DNQvy48sV%-clFKv zPb+ky&T|beykcUy4+>;wV26wUmhI+jSx*l!hy|5;hDrg5qzofNJS*qhxBZ{^n=XX6 z99LS>2hf z8J=WnG}4rU?0k^1_>d!Oql5{|a3PNqTMM4)B0-oG(IZE$t?EMm`~a(^&jY`D2H@-!E5BWg=nU!TT z-)L@a9Wlrp2A}DBZ*C4^j?g;E*w|RrNPy=fWuC!aJCc(H592matwz|3Jv%5>A=MEX z-da7g9$QS!*w5)B;UVh64~1CHKqt!SW|PsK>EEb#Iikd zMeRNfQZ8t;K4PZGTsrp}nxtb|_;?=6laiLGss9QcsVT=|B|Tt2mH~dYe*&s`ir|LRH86p6#e3i9dDhOSZMXU*RvhGK z5l8Q5Ok7I6OpJq$aZ{@`i=iTK-8Q?F%Zw-6xV|V*uCFmajI>Dyr9c0#QTO!U1y1@r{eO zA8XSTGiVsnPqnzR!rYkWHJ2T=IqPQiYZC{gkxHjLzGOrSyrN$mJW0S{dE0U^Xx|Pv z2wwor1aZ=~{>l&jIa%w4W`Z>UHcTOEnwdrb;D%^Z>O<7p*FTdz|7y8Yjrd9)uQ^}u z`0HKJaGBb{^f-vY`>}|SVGz$>X{VOj^>Y5m?wh`?3jM^N6A6=4j<$N8sjS*EV5NFn!WR^ybI$9QInpY1+eB zdr)r)(O+ZM?!rU zZI1ch9)p3(_n;a*Nx2WRB!0&?@7-gzi{me*MU0&l+w$pYhJmA1f`_vZ`hM#2QkTE0iz~z6n+-rGO}l?DIvhRvG(*Sy@}rSROhx0YYWT$!!*ZTW4YiE>X41{% zLT5}hd<1G?cT|67KsUNLbz}?3Um9Fj+n+$Q4SmZH@EH}`mlnUsvmIlO$B^OdES+Ab z7j24qJmOxL-q(E1S-EhPg_TR}yo%HNiVIc5itojaIoPeXAAlJS5c<$zoniOQ*XIe& zr7dR)#=3n~tiI|4SEb44di?tlGMt|}mSJ5cXQt{MTwk!jN6T>+_i9!<&Vpw4&(p4- zPGLrF@!WUMAc8EplSGPS z&+{!e%JI0pNVSfbYJYImLYv|T_Od^XbVjyuL0P!JG(+Sq?%h|WXrv~WrelIFr2aL) zHff0}39!oID1O9QKIMTlD&MXMH>6aG!5O1KrYXoor~=wgKvD<>^6q|Bv>3VeXO-z@ z4}s5D@1&R`>4G%%`!yx5_y}Sn^MyrhMgTBLL;m13TP9;(p;1So|JQKyehM$=7yVd; zWv%(GX4sRDMUDz&*f4Kv7IdZfz>|Knm?|j9$m6vDcKAIM2t)7x3qvb>v<#1wY~=IE z@L0yX4UcpI>J@K7RRGQ)>Q;c{>R_Cqd#}RhKj;^3c#HN5=9I5Ej(4B82#1~0hbMee zkBwI$&q!g2OQefQroSJzPDZn`NoBRRYHhORIQiq%;X#$|#ocAOh@GK1Wo@0D-l7ey z9%x|}R@Yq=7xV<3JHsi*;7N+7e9=m?Sp8w+;EuM-wwTBE?=wOwN8rwTxaeC}R}cXz z=8}qR??pq%)6kX`62|rlF|U?v#N1E5=H=xfk;t4J910JjlCJxI0e1!;A0H%IN=iyV zwqR{2!+YyzPXyi2+~~|)c5ms%ySg1{(O6W|$WTd$rUWyk(rbi`DA9+y+-m$~sEFqO zH(L>dl#_$Q=RYkBejdC5rls!g?hXzDq-yHwz!v!T>MF=mJaiOfLt6mvgWQklVCwgj zPa^5A*)o2}YJn&5pH^RNEiElzs1Cf9 zDJd!U9$;f*gD&!QNh>JaZPidy!;!{Hz*xP_Ncr4=Ow z=QMy98&&oR#7%}6RUT$MpVn2KpS}-s0a+^uSR-Q5YXmxL6^X=1s+5(VdjW=F&Jqj* zfI_GYF@xY8KCFTaf}xG@Cty|bWR!}ci`Ufus^Mc0Z{YYf-q@KA9qD@8l*IL~)(KHo zAqik3={imaXv_NOTQUB-RUP`}j1vY<8-{OUk1P>_dv35k)-(R@(J;yr}g)?t<;@e@!^hOg-G(kqstSo|g?(@^n$2 z6>^sq16cM0{s#hYXeckM{SA&*5>=g@(PP?L6gJ$*AI^W+|F|uaJw47AHP%VvW?t* z+9BpBFL)#^!=0bfU?}k4y6&q^k0kABqt&4rEzpduN!*zc+Nu(sFDSGfuE1|GVsIT| zKgqO|wD%gHTcQ2m`gZ`i`Wr&GQ_#||&rOfCRUfaKtGwG}O=UO9w~C2=Lgv50wFM#7 zJP_-I&+g5hz)#bD9sP_|CMaAhnF4d5inpK3AAFZx|6-sVYvkU`-G=t923GL{S$WQ{ zX*FR^d`+oXy@S16U#=-XCO~^nnU;n`9N<)Ok~!D5w(^DMR>FJIkB?*pPI_KVskqsR z0ea|7R=+*S1DA8{_3Bp^Sw!V(<-B=+xr}dSNdAqoRK_iF%HIhzv9~o3lA6!cl{FkOH zKr64ke$GHq9*a|ej}S_TFd#e{#kqRu)pmoZ^egv@Y}5jtvoUlk-six24+@`GNy>&z z{$`o{ZBi4zdiiNEL7VtaUEZ}6B!&)M5V5FM?K5L^^q)&EaL1kr8JQ)p;Ilq72pU$e z8!NXorBvc1%ol}qIaDmTzju^KPlZ}9Z0@{xG_kBxyPCfG^z`^SEoBTz`zSD2~jPVhp-KRQPtnH058EjZF#Bg)l?G#)aJxsf$(7 zs!`tBZBVJ=Wo~P0Yi%9KZfR)=0>bdHFsRY<)q$?GnENl83CuUHk+!O8LB;^H+7 z#=^{u8T!vQu1yvr_k9Rtr6GAnjQ?W{6&G2y*uB+PGs~ zZe?xmL7V$8%o>sd5Yi?EEHvZ_64H46y~=zU4CuNI4Go_!G*SuExzC@q!Jf1@6%~e~DHRm6GkhKJ?NWe{$PCSXCwW;n4#F7u!5$@n zTVFA49tFZ}$m1Lg{U3l+2#8RwbRaO}rNVO=pTcK41zt~{h&oO*dFcLZe6xV#jnvXP zaS(iuPrb!Co8SHDdp<^fw9I?RH2pWc@>`(t<0qQf-`!haP-lU_(o9zA;i*pSeO^MTfjtK!K+cUZos^BM-nAR=9w?W;2#y-|irllD zvO1+y@y8ud#9p8+Gt7Jk;XbJM`dMW5ah~@O_WJAIH?k%jG)eyfXHnKTOW_C$O<{RN zLE&u}>vM6KVlOYNLh2K*%fG|O*Tf9ZJ@yvAdjgzmzR4Z@_p`9=JHQb+Sm^`wg$p1< zF+!cboek3WYJtN+%}IJ~rkYioy5^Txs4q1aG86am#N;2Q& zH-6mjP2gP0vYDyGhu$K^gaJ&m{Sl$QEcq&f2f#F2eS1D@YiR)~_hB_%fMUKdj-J}!2j{B_4;htpVhJFq}y zviP&eu_RYgfX9mZ#azxVLv+qs;TX!s-@HbO|EY2qV>hGPQyFU5>ur+vtTb1Y5OP?b zb}_Q>0WDj7eRG07s2{-&8Jm~@e45CZn3#x&h~VJY($dl%9v(0lZnOp*j`?hv9T#~1 zFm^_8R7PaEssis8eagSmR9(-y&X!tuLN#ik%ag846>GSc9$W{l#gV@nwAM=QYC!wk zS1Z31{JQGA8Q&`PKE5o{ElK-kWL-HiR-iSUXvu8J-2*#MDA_BOUTW^MrivY*m_E>f z4D|HaxwxDzQ%?Pi(B5mgUDlv+pN?*)u47_?QkX?pSRJN}^PE7>_#KCO%C4p8nXikn zj7VV9Z(VIb@$q{8jS~`&gWJwF1FPViu`;sA-!`;_Ra(an3U8*4J&T>E|MsSL&dj($gco--7&7M@I)_O-V^9x{JHj z^6gtnueMl_HH(e)V>FPSV})t|k_#0FMgW0Wz{{v~M-nSmb-MH+8k*T8c^?XEK{tO= zWx<5%wMf$TuPwkS{q44?_iB!9a}W|nu>51?#kT(}j=KD2>0E($$t@j zUZKT^e^MwIV|a*xT3=toZt#1diC)VCd{`TvU{uaCW@6F|`><}X1WKO!ad$@ zmw9%6W#5ddg){SnPw9&K6hG)m(FVr$^VVd874pObKg)Su`;q}){J&8vQbq-v}- z^uc7Rwp<-L=V)dP>=|%NZs(7k+TbS~%B*Z{8X`_+KZB?{|8+DodN$mG5t}$*DxQ>8 z3A#Cg+C76jhzAhx@9N#_0!}g@a$Fx&u5V4a=)OWmS%^RM%17SPyO2%UaPm0#{p;Q3 z5OEUfm`Sgv_aOK{)Rj)}d5U7V8dsZ*q{w^oy?M4)SVQu8l&+NDb$zmQaq4+=TUdN@ zxvVEIYg}!~*#34El_f3R)hm5<=q>aLR~ccFP@^T4m6v|RJKd=omwrwXPP<~-qNu*I zeM*kZ-#n?3BS;l2up%w!yO2JYN&Mq#b@1CLT{7%;AJY+MHQ}+_bKgB}w|X-*kG-{y z^?ODlE1SCyO_dvUCm#0-B@i6DncMpfAzy>-bKRvb&=vXeIBJeNq-M&64&W#r$ zH}83Uy^B^*^{9QlWnkwzpm)8-P}*{RUTgP@MJ{=7-hI~-nE0vW%B6@naRdc>{ijSP zZs_$MidX;~YlSQ+Vc~-yl@x+Zp8q6RmwA<{H`U{cX~p0S)Nq@>~`FL4Z0n!rEYTr2W2UrG!C_BF-r|V&5y1Is^ ziDs8!gu#GtAxp05v_85Fix&NPfO>YDwdG?})-ezi^D*I>k4{tn8!Uc(<_+A%=0E<5 z0P`Q@#^E}p8P7e>selyK@uZ$nVgt2+i3fPs`9E)f*i9^`d1A2jR-K(YoGK0K&R}b* zwO*P54-eJt@)a*E(4Fn)5?loVTyP=VDU)a=+zztL6Hn zrlsj@^)n!*KGu>3QaV3@l+GfM(z*T}r}#tqeA+Z4GwrC4x8;=zdvw@@vL8J3_YFMR zFwhN2Ds%f7#vCiV86nGrKSrA%O|%qo?Rgn26!DYzC&vR%m#lcd3D=^N6Qkzus+;5O z=UlYtguPKK`c+Q)YyhPiXIhy`7C3^IkDK$WB*}S$nl5slyz<#(+YujRZ z(7yUpvBlG6vu0O5ZGXO!+MHVR=HljZ*88%{yOr^3_vYI6Z+8AqLK}8{FwVUyPx8nM zG=hTRvxZOra&Q4i<_;J z*Sm+3oX0hEvNocL(S=P$<_`fTR;S#}1E6|UZFH?APz#6}C}xqnjvZAeWA&EeI}aAW zT#E9(e8jw=cXO`3nW&uHCP49#AUmr$DsZ=e>X=^)z{aF9gm*s1N)wp3#{HLAz`9|f z&35zd+mqJfRA)ivwWvrQ7DTO!{=f8wMj1x>db5W31K2{eEAoSMsN(-oIpEP^K|xn{ zO>cM24CJ6lhL#yqk?k2XGcy72fsr1%pb>_|+2i^ZO3x2l@K_U5A)GzU_3YZJ*fpQc zUyNwhK#c6US1f8d6h_zgkDS0syoiy=TEu1{LEke_k&97Ju}~4j$Qwg=$~Vj>^>%t@9Rh$@$Ws zdg*;}dIMocD14IZ9P4^K(;@V*<@)h7?xkd$kzt&QGGV;-XqEleHL+krgd7!?&G;FpF zT1dcIZUoXVfjB{-!$T(hCj?@P zLhdN0#ePbQ{hSu34ag>kmi0jb))gVKz0m-cr3_3o_S2MT;)2Q{29qn8*jStva$ft% za#-A)pMSQTEcw~uE&fmx;8frk6Eb-&^7QH1*_qUbm=2>0uvnx#^6$9NwRjnOX?Q<(E z{RFovwregjfPH^!h4P8mjwc4BhJAL1`xVk?-8}ai2{9bw!@q+ZxaTqQOm#EZcNq5h zIQIB4^y^XSSm%*@284n+37Zp@&q2U0id*61rVSdUTj}K@YmnyalH08MQDB`G$e{Q^ zq^ML3$(Y$aMwSfY*H|^WhgE+^k`9&gBEsTGP7`Kp7C^Xytr>!@gttHsACT{jiO7Q4yRdRr2MTdSLx@9Z+Z>2t~sZzYB*2EvLac&XXFw%EiX!cw$=%VEgOn1}M)6>5Pj*Nr^ z1pkGEqflo4{$q>-#q^J1Qaf4q;XVA;S8jG|u}Yz9HK!%lhuVN(JM~d+N)1YQWa?{R zbad~#nWNBq{8*UUc+Cj{3Udd?h#fK-w5Jsrt(xy}3>)89WpUECCTn0nB_Yheh4x)j zeG4D|f7CMA2T#C*ZP7gehnPs|G6PmLVic{ZUkmvu+X&xUr{O5dr}+=odob~@mCgSP ztpZx)7^A#dcflXXAX_d8Crv*s9iK`C8Ng1>&@-E}hQ7DNswT7`vpjMMdj1E`u(G+h zi>D;=Np`B@CzTH9c~&2h=ySBdL@G{D)bLl?6k&p3$LuD!E8_77h^GO-j7#>unSXx$ zYrBzas2@v~8`^LFSw_**^|RW0W~QUDDB2!bF{lNtI_HyYBo1<$`JvIu3dy!eGEN9i z&>?Be%I6c)_^RaK#61G`0?Q2=fct@xRc1&;ag|h4deO|9YUEv8RVOcQfZl^vXld)W zy6|!T{Ki^b`@NfYsGE1PoA-7hAe%e1-F_54`~(x}WL7{&0VZ7Y4wnOZn=b^Q6__l} z>h>=NJZs`FN*W7kXKw&h`6vwjc}gqf?T#23(yg4hb#+bk{(j zn3O|nI1$#LP~H z-svh@@ie}82l+_@4mx6hZJdvgR8@15e_2* z9wj)tRSyfhHl_OHt#z*ZP<4_*0bmRuV+0Om$+DW!q#;DuRITfi!O&@>!V zc2^X=&4Wk!P-y zRRT`dP#xgLfIJ>x)qed-WNXuAH3S*~RB)V~ozYZi*8`?^=3Nnn%6qV={GvLI=Kp9e zId^NzNTfRz+4#LRS~?oo!ZOr?Oq(^NXiNZ64g^5KNLg^T4tOmXkg4Kh7dBQJPX)5F9Nk7;^ z43BCSyio3&LusPHr(@zD_gee=`-g`~b_x{Z65>PODSxcz{zp2srPjI=b*U$1h#T|`aFs_0mZ$Kx>37;Lvr`QYp zZ3;}rQg36;1eMeGM{<&Bp*K1@S)+zlB+3yBN=sLBUzp0#14MiJp>-ANYA2ZS^){{kws&TqOf+1Wm&e>uk3!LHVVG=qbkYY{T z`(6^L>|SyER^uP2-2hae`1j6)w*hAYpJY3E$C zpK>P2T5`8o7cY%T+y%FjACV_NXJZMG-_^Y?V&fR39n@*Y`~ zm$P8IrQn@IX?}ANs}%d*j9I3cxZGcqmwva79Pl(_|M+pzd{ZVynDE&;YD5vvrf5o} z;P`w#C3Cm=UELX9oiE3D3wdIH`xZ>d#<1c2`E>=28E3+cno}N+HF}2Nwwn#!qs$;v z$xYqcXnIslIFKX#Kmj&M;Y^;#Dp~?v-|F@s{H+h|Rg9-nGiC=hYh7isVvn#ZTA|z$ zd~V!%LWS8yObCd_16H?mUEC-xtQq|h4sFh{p53!uv z)XL5Lc2d}HH@RIcWiYL6Y&-@UT!lo#4A(n!jaXePUNTQJ#q>s6{`m;T~Pji4V zFrqMFWy4%j-X)#HWv?}S7aMsQYSlV%s@PR@lKq6H~5IkB9oOKcurInTmdQf@_W?}#o$?^qf7 zT_63g=p@30O9cd}*H^_dG&BO@%Qqw*bqn3VOQ93>lI-Spt#OK-fq|5ilxI^FZi{hT zfPt!fhDl;^(tFHB6J^PvKm10)u zjEOAqJ`1GD!MW$}ev!@e{S5AuVlqkSrzNM$I7Nlms>!8sUn^`GAv-;_gV4efMS;G_ zH{}?sEB6^jDxcI{d1#@BD^LgCau`8LMTKN19&q`OO$0a9_P@tBxb!PR^58^QO@wrD z?vL(&!qaKi`7)sPzmxerD}-iMX?*^+D>Y z-^+Vrgt^fX&y#U)v9lAs#ep4+_kKmvSM?xZ(gO;PtA6omp>kQ^`^f&gr^?)4cHo>rVfD*D*wKl40liG9K zTXT$4A6vvu-`xC)d-o$LIDV^FiiGpIEw|&hM<^qd0ZU%HY6se&jgBlqMzaG8;LdV` zyS$gzCp)t+kGXtwMoUNM{_;9FRo&YQC{P-Xlylp3cRSxUbn`-#gHynpC4;l~;L!2_ z#8LaA!Vtm9si>qj{U0P9Z1R2^@m z7F2HLDi%2DRH7zSav)U|6%8)C^l6`7VIrSyCpaTZ?v)V<5H`+GYSis~a8?Vp_VE7# zD(!t{4-zb^cQ3EjLr1le980!-dg}k3>K_@L??9o1*`Qn^4Lsq{mTstOkjfHX&t1?^OF$I<`XUtS^%;NI4pAZHQ6j%f^D5(C7(f*mD zJ(|*0#95ll*%EZqP5|H0S5ummQbmO?q|yI&4R|I!E>q5`tl*SanEl~*rYCbsLDpt> z0aF%iu+VHvFJ;BLY3!3GPigstT#6Qd-#OWQuzxL?RKnxDq{ls~Bk??xrz*Ir6RG$K zHSZH@Ow_-mR%UvJ<`+JqD*V&$Zy|CRn!fwCx&6o^W|eALqzOlLK_YtUv**QDIobD&sx89p)3v#)uQ&0;2`6o8^a?%T=GIJdw zfDQ{0k)xg63pw%5OYoDk?~hb6j&L!N%hT!KY+kCOJUNn_Bau)V-R`y?H&C1ndKCrEj4vyc*N+SJL0T^=v zOuX-1Ga{iKV_GkVg`(9|g%XV4CrBqG#-u*v;Qp;@K*BQ`w|Bs5V3?2+97?Wb!J`uD zY8FaOuFREa{-MnLLyU}4W-1n;{DTeH=%Qpc-yQbH#DI(X)`9|VL#Jj=rfW^5V#J`n zc293N{>NhKRDe4pIsWzYkp`JvD}p+g#%~H^M0JuqSE2V$aQdDW;M+?wDw?&fEN1<{ z_a&^1EG&OmgMrJtCO0tscCgTp@Rz6c!3i-ZiswLBddVvW6=uuU5-Gqj=U8t1A*ohFAAHOPW%oItKl{q9>N_kHWHjKh)sdZ)717!w#Z@}D2m zt*+9JkB$lm3RYHDIyyPs!Nc0`R(n-OU3ZCGTRhJA@3hoZS35g6 z_%q-WVFgJ%yzIk-&Ww%SLQIT}>Cdr2!;(HP({Y!Tl|hs@H#YF03v~`_rwiT;H-CNy z!*a_4xjkbX^)o6JgH^-e1=_MQy%*WH=A4|_)b`sMog|*Vv2e_SFnhhO2w#K{++}}@ zyB2phCi@5;&rd$Y{Y@biPk||p{KNgf+smqtE^2Y5*nO%pO5f{!6mIl^i;~O6OVwh- zm8vL?B_4%Lvd2!XaMeT~3Kxi~oG`_Ar%KN=60i%gW<|M$YC=`HDEGxeFJxYwbq~ii zmJfG}@5bm2KGJhNTY;RdEaw47EomznRlN5YoD(q=kB1+a->JpMzi)}5y zo}Mjd?LlqI)H;83Dj97s`z5Q-9`AR|6702zndKK>=Gjt3=ND585;WD`8x*WOy?Dgu zBKmtb#@;)zCGTjE!^x;)o=5yXp6Svz8`*%H$X84PM}OWtRWN^Jz`slmg6APYntuz*Oi)odqCNvhBqk*p;cld+-ro-0^8|>JyZf&YKpp5V zV$D1-8Cj^T$B^4YxKVYjfjiz-fM=7`5I-cwb1T0)yxiPcdNZQ!#p1IczNtzbGg)&+ z><;3_UTmjIaQOdd?@It`%=-VID5(g^GD$Aeq_Rx*Y@tn|&|=?8Q8Y@0?E5lV-o)TF zjAUytwrMcgvJJ+XCD~~hWhfIe*8bnmb2^^$+=|S2=Y9XbarxZ)ENA(i?{>cD`<#0_ z;%!;tOx%GZlc)bQz&ayy@$r?7uAG^9G`XesjXD)qcm;m)JfL;Xao2{HR+eS!PxBsx zJaF0}pDRZuuTJcDy7}t1mU}#M9yHC0AA96N`d2$woN^zqwc+HHspUu5&aC^gQJnF& zH|M73>308iF@3e7Mt{S)E(gP17cK2OWa6o=cUG>w?P;)MPOZ)x`+4a0S>X7Ip7kxO zQ-@!*bbe%%WmWs7_wDt@{P#`{kB@}-yXD#T9s3E{t@f;RinF})g(7@GN`)7 z!^`?u$zzT5K5sg#q*Go_n~5*z>Fljf>3fck4@@^ooM@2ZnbGTMPL5&OvhpwgR(So{ zLwoBvXD_**`JwZXsqv#L?dcRWp9k)N0{9w7|xtH$lJF$FUKxVY>hKs|}b_QOVcWrF0MXPbQZ-3ipX_dqgk(;jV z9{t*JK2Upj|+zI=Gnz^BIUnkIY0(0kHyNDrB^!YN>g5J?!V7CHohZ0{Oa3# zdq}&5$@p=nAs5zvRj2!=DBr~{vlnghn{8Y7;mI90%6i#fc{zRd%>Li|MW=J z+jE_^Esn~T>P)*t?O43Z$?$d@n?cY0E7XamKa7(XH`QXH)2!OP8g^Y?J6re8ATyV~ z7WJ(zJ6*YQWmi&C@|lURAFUYgpSW_R&bKLZq90o8y4M_I+WJ-F`^V^8!p4*vwJ|fk zxuD&RI0q>(eYLb*XUHS zJa{QJIK*s1&w)=pD?OcSKG5fC%jfAfQE^ejD@ycT=ALn7Hr1>eomHc8-zni)Sy>v3 zo%-EPJ>oO!9FV$f>3Tn!_WMm(d)+$r?EEJQ7Z27vTvK*x`dZ5u9oaCEEp!OsWYzy59d z-uVOPEE=odZ@-@I&SBS*^d=p!ao$|+Ud}@&8>gsDM(xET}Q?{oXr_T|TaUa?P~$4$D%rjMIt>C(xeyzvs+@mb}Qq|uM8{Pkkm)D7Br z*zscj=`Oz=2=p;bYdFp*K>Z*i`=j_KN z#?(qTomp~;UabE{hf^~xYTGB%7fKR-nR@4F`8ea%{_QI7j~cf(`OeF2J1irgjcJy8 zqu0oO_WwT6eR`+T`*K&@Z~py+2T2xlk{8|TJ>c%9Jwfq~_4JQ-p55ede6_6_o!DD_ z7H_`iaCfd(?6PaSZrx}yW?I+b*~uPt<0@wu^e;bRsJ_1b&KadExLj-nw(alYmr>iz zt!0K@_s9WrN+dNlt|7VVx1q_Y@^>XmxOd&9|J`thooh_jKI}BV5^dAgRBG<@qQo|P zlj9efWbgj|SKCvT8(UrMIdgmW8tZmWyiwjYrv8zMw=3lRGCU=9@5Beo`}y`>xUApF zX4UPZO!W-n?hkHP!t&tst4S{&{+RXS*+V4L^=@-w$2NPkdU^FTnYSaK4}RTzd4!Ed z>M=VyY3r;T+pf;4;SjoY-i>YhzZ~V#x7nlK+pTlYpKIrlaGtiUb@1|ekQrw+d38{2 zz3&=ytKqRGaNT)nj}7tuV?KUKd%H(ecei^NGGjeX1y#~>-m!DO+4y-`RbKfm zY_U4=ct3oDH^npB+IG%tN4*+$E<vhs5_m2G4{nyMhzO!%Kn3y-pD6`!7mzP`a zS-<`0@~FgdDd&?~E$KZu;81d^<=)UGM!QC>x2?7+{rdD?SYdm-uFsx5G&_Fqbm!&kD|HXu({J1Ly+2g?J-2V>MTfkXV}AAS z64|JI%EZ_E%=_M{TFKn2fqP10X@w8{H84%rM6)imDa9qq_KwX zIq7wL_swPW$WasNAvg4XD?3lG?bzEMnMvrb89y44uZk2DW z@7gtMs{Yi|d!WIj%T2C)5fc)o>*Suj+ejy)(T;k{8a>ZDn(iRE20vVIbAh3yi=9oE zxt_I?O}|?+Yr3P=8S~jaSKEDO)5qu5gh{{m@EI|7VT~id-)vu_dgP(d1BM>$Il+N# z2iR}iU$5L^_eHIJ)C7C%8Jlt1Jgi;AK8qIjKgx+-b?5s2-_D;-J+jWPpM`&m+0k>l zuQKjG==s;Tn;lww8$0(@pK0g3ua~QC?y5J_hr+NU2FqN%ZIZHs zhuVZo-^APKytdg>G0wJc#z4)u@ipsM9I@)`@atqJqdJcpKOUOhe{AUDy5r;Gm$^9q z^vgb@9aVpsxU@mvvMnARt37zi>NbymADaDm{pDJt(o=Ho&|ex@xPj7?q~2xB&04># zb~J1G`k#NYP8zlUuvOc2?(PPC4n~*u@VT{W$eFJbPp#crA!DdVQp52{p1szcvpQx~ zrGDD$o~d&`-@9}EtIkupjyhH4!Dg?|vxb^1Fm3JG*s#MS8_&+8qxXBZUEkI>amBnt z>7#Ng?%fx1_|r=*nhx*Zrg>)jHuEb@uXJnZu&h;;ZkKO-!EW)+KYS9$o;f^jZou5; zJq<1{`+4*54c<)-e)U?`<~S3O~`gZc+s!6U`@E!y?n|Ld{1G ze(LFac;NY~yKa0FxALt2cLCqIG%-Ka<3VujlbeHA)$7w`tV!C!^^N*&OEIV!U;k^% zulug3mFDo`rz(jTA)mpCx9${IL}*n07u=EnM-aG5dj!oy~n^p{heZ2gS7VP0*w^~=nI zpNGQb1ctG~2KhTE}`t%;@h)L62`{HJYPzI!&_bdvmORyZ)_Qtyk7Du&}P)u(NH>)mfeW zR{D-l0B(KEr+W1|xz1?F z^8*K(AKRQ2+rNuvXvy9)f^|;RaaiI%Ex^9(pkcocFnPLS#uIR1=2%j6%^ zhw3#;KC>&yF7i)R5v>!HG1aYfLwy=+lxum(gc{P;h8fNjgB+{_3j(wex3Q z^@xl9C6t=osGUm6>Bpn@k{=28S78p^rSRX@3>QF6;erTS9Y{2GBo1$rJy z^&+Geblr{04x@fT=!%B=RreV{=iyXiG~J7!Ptc8WgXCTZ6LrBdP!J}!p~x9P+N)> zF=?UYKv{}xM81+cwTycaL=pODT7W)bdtK%Jon(HZHD-z0<+(13eLznzHcmaaUM3ri zKUC(Ih9nr8&o3scvIXQ-JgWm2+U57DT?5(%>Y%^4$0+lsD>%o;o76f_#P!Dv(a zh3XpgJ6g6ojqK5&^L`{puJ_%kZP7=fKeQ|IgX=c)t{6S24wd=D>~WAxhoZ;KGqN_s z9?IsoEBavOk$k8UfZV%SzO3X!cR+bz9v9q&j9^``Rg@b}G((qz z>0Qltu8IEC3&zSM=u9PSf9sPhR%r9Lf zC!*pDqB>M^Bt*&AyooMI4kIWldC+l`eC$MRgv;8X<_`TZGxg(7wE|UqM*H5>Cp1iH z9kcC-{L%&QI?0?KC=Gp6L)(9fW5oy+OJQ>O@6KJ2l4zOmWY7raMY;50o!|;29Z1KK zGH2OrtCVEz3?iPZBL;W?%njVj!CEkO-n!xmQHn=0tX)4UryZ9tt&OBs0_h*9V!B+= zl0YwXIz-lLKA)gXQ7ZN6T;W5(-qf~&Ug75hc*!NfhUjy0KI1a)X^-XMmwTr z9_ZcCc{}Pw-9o|W8`NNoif%CrMm@yD@JB3O5xtg1wWbm+RGcwzJ)HRa1+~w;rz_2g z&{`IYqHky;B5D@pd?CvN`e99d^GKV;&S(#jMFdF#nh{7dCu$?k0`Il&drQuA4RQ%5 z9@`L?H55e_XLZB)CXOFG;$zU}zv4SVwK6|2D`U|%uPd(QKGC4nDB=&J9hwvyHmWp;oDIgvNXVANvvpwmY(^N1@5j_u9rqFRF z`J#DVbUzAznLK#x!R(Yt6INXKNTGp_qzB?UokzyvT&(o3jO+bYB+fKaB`+cNX-&~^ z7ukyisc6wiwxpd3ZSWh+uc&hi?ceCM4UL9T?M1!ue8zvSud=GBp4k{Q1p204*)kpZ zv%Gu%*&RIfCaGc;;Mp4`69rCc-&f*ScDFm#23#$))2g;EkJU>ccy~x)y zV#JDj>Q!DRYMW(spu?(T~UifDJxnKA-8~)Cac*NIye}S`V|BBHwy4fd297Q84nwxLuWml;nCvB;Z56#JS6a_Uao^AbMn(F8<5_mOomy zJa`At#5^R+Mz9P%GC|t;u7a&&rp0_2Lh}gbejl25;cE+J;Ka%=oPn4K$igOf?)kF#K_7K&f2Ixhk%GZC0b=7(a zJwt|(@d~z3P(Cc`MAnea`t3;e$i0lF8JOjW#Rw#VV#}iA9q>CqrYbOh9xN&{;#!2c zOidrSgPD#=0IMq{*QT~^ZORKup~f^{TTPZ&W2 zSurd?(O5<^G#9cetOwMDyqImHC6x6i4PyB~w%&nGAtTRvMTEgJkKA`EZQ}}$qZMs> zmj}WMB$PCi<%>bTNHL>9JDbfZ7j=+XGB_aiC|WhR#d1xkr*I1EYnIjEo~JNRDcYMD zZ7clKwn})@5E>68!MUaMfM+AhGYQ2i-1225+QQo`L8OI6gz9*fQNc9NjmE7!4dxz4 zT(4sc;#wc8%>SRBBPtOx(gL1*0Xxt(nc-)6N;(8p>Kg$+FerOk~ zT`pB~jmR(dd<)hiu77!1SW3YsRhS=`w}nQ0CiS3yEu@}=Ub3J2jO@Q1ojDSm=!%u5 ztXu|G!}1ciuaPQhFz@qcYb-;c(8lgNN-k8A=P{7qP%`+?BuDw_s&XImIXpqQOo=yf zO{pCrQ;qTP`!3|YmHUD66D{~ywCt(snP*UyGFWZ*q>>o3Bf&|kN3}%y6&+=>eOa1A zz&B2T!ViCv7^hp*ZRiL0k&0(v9#v@_)UsSA%i6&YLW1BnGzJ>Q{cd4e#{7*Ub3CQP zoFnEo)R}L1FXS3TX>dwGvqCGR1^=y3%T{zn)5~kHdE(vl^77DnPB$AfC_xm#{HFE@ z%94B$-Ls4(<1%W1XWG=l+bh>NFL@-#pCU55g*C#Lf^tzG&^8-2Y?Zg6=o6nWAT`7; z>L)Ww?`TKO6=$dmnC0SoBJ{|f7pQmc zut*Opy+Goy!ZEe(qqd@nyg!8o&;|J`^~IG0mjq%z@P^NBtTgjEEKWv?;3Jz!x>BY| z$$+V!=v!&nGmY+41N4Y(4b7Jaw`Xlym`C8FP)4fw2lcZR=Bt^GU`>lP4C9-&kJ7eT z-iMk~{A%IRB=?8kk1%QbB8r$vzyRA@X;>+-9~CD zRo7q*&0=N#yq(QaA{SXs2mHa<(Kj+`k@QR$W9Up#b0@mTS4Q4+jp=m3Jb*GHtijx= zrXp8yb&4Gf@ZC&)&>yBNtTgkU+PN#(E%V6CcNNTAF{+gwp|cSJ?eKEYSS2^kGy^jc zcA&wNpcnXjB{Jd~!S(a~b4<{a|4X|*UF1lG?fTG`68MIFNbrQvG^SgSHSAYI+Kd$t z_JphTQSo{>;yj1fW6~BQF}4n27R9xSMCPPGd!hxrOQJB-g#Hotrz-uGYfHyJMAkv5Yz(qb2vAXcY z*xd^61^>qS!d_AxT8;62bew{Maxad&xM##{tBgsJp0~_pW_69+>Palr1!l_dFR@0d zN2UBKVjMh!VRW&axk3@YtA3_cIBlQ|@ujx*`I04dlIa$o;jnB6R_tuApO^t*b12(; z$~_dHli_;`j|tUtF6IH2sb+Da;x90Zz%#%@1k-nEl_xg*Ne?u0Fx5t$f?F3`S@H;i zl>|rOaongcL@~@u6-KFc#-k0@awlF5BpODLje-l@tD<+FX;+?LvVF6nuS0x;l2~`b z?*>yFjB{*PEo_+G!TiQs1-5DPb95Eg^vrU7Px~ zCfy+T*ifH@X#_9&i6E0Yl60MrSeN_;!L~m2M>yJmWYLIpi!g*RhcJ)u4Iz%Ony{9z zg>ai-NI&~hhG0f8C)g62HjyNILW!nC6JaMInP6v6{Whnu5j+W92tx=kYS~c9YICI9 zH!k01W-eb#AuHB?9X*;U|9kPKutZf3zS#RhGVm>}Q*y|(c2fQkWK5DZB3qrL*lIzW zH*mDgmng3q(8=1ycc--Pku2SGq=_eyhpy?%_qLpm1xfYJLdmaq7Yt) zC%ON*lgDDyIpWC!@#Hu0BvU-ORlJiMVzF!DN!kZJp~m#8NQPFDk*lsm2_+e&^RJYY zOacPXUH)}ml731`>k6IbUy(lf5V09zFEO@4jDWcr^Wt+*#9x2#1AIObPkt9qvc;2o zMV@4ccYYO5Zi^@B;>k_%L`A`M@y=E8kh?(U$s9WQ)pD ze<||LE%A=ZI8_v=EcJ?5N7c_I@s6s2i{c%XW)!Uqr^Pxa#S`sgEvYI}rh?k{NKN`p zJ5-|YG>W(gT*BnswMz0k`Cg$)apNlr59-2%j7ssMj!TNkV?#DFOyVjI>^h%TaUtuU$k**DM?4CBrU9QP@-fAJJ97< zO4F5+jio`2r5X#5N;DtP;MvFvXoR+gXrCMLcs`lrtR2&w@IRiRI)GTiCF)C>{w+n|7cy1^srV>CTOqMKg$1~Fn36L$jv+_ zi1``hWV zp*>~Tojv-!hFX~flb8R3{**ERw`ol&zta}kLSE3Dws@nL4t+x!JJ-VUf3uKXE&jU+ zNf$jr_drH*YYxdTs6+i?uil@18B*`)7sDxT|De}2zrzN!qn___{xdWfQ~$6(^o>_> z+Cce#!5HY}Ebox?V<&&&osXaOUcCM>_SrX~Es&cx?VrRif?zNAXnAKN`v!pceGIv1 zp>NhSe)t#on&OUMRz21|?TEzQ-T?V~oZ{a>D73ReE}G@b|9!@ O{h#Td#u1P|{{II Date: Fri, 27 Jul 2012 13:18:28 +0100 Subject: [PATCH 075/543] Updated history file --- HISTORY.txt | 20 ++++++++++++++++++-- 1 file changed, 18 insertions(+), 2 deletions(-) diff --git a/HISTORY.txt b/HISTORY.txt index d0492dd1f..7b5990e28 100644 --- a/HISTORY.txt +++ b/HISTORY.txt @@ -1,5 +1,21 @@ -Short summary of changes. For a complete list see the git log. - +Short summary of changes. For a complete list see the git log. +2012-07-27 +Added the ability to load stylesheets from external file according to operating system: +macos.qss, linux.qss, windows.qss +Files should be placed inside the app folder. +2012-07-27 +Several UI changes. +MixerCurveWidget refactoring, now as a simple and advanced view. +2012-07-27 +Added “advanced mode†option to general settings. Right now it only shows the hidden apply buttons. +To enable go to tools->options->General and click one of the checkboxes to give focus to the form, +then press F7 +2012-07-27 +Made the flight mode switch and accessory pots move according to user input on the input wizard. +2012-07-27 +Changed the board pictures on the uploader widget +2012-07-27 +Add more verbose debug output on the UAVOBJECTS saving code. 2012-07-10 On Windows the installation mode was changed from per-user to per-machine (for all users) installation. It is recommended to completely uninstall From c375d2e79d2e084c19bf3b5741a001e68cd18e4e Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 27 Jul 2012 18:42:20 +0100 Subject: [PATCH 076/543] GCS-Made the changes to vehicleconfig final and reenabled the system settings update call. --- .../src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp index f503dfba4..aae872f8b 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp @@ -105,7 +105,7 @@ void VehicleConfig::SetConfigData(GUIConfigDataUnion configData) { systemSettingsData.GUIConfigData[i] = configData.UAVObject[i]; systemSettings->setData(systemSettingsData); - //systemSettings->updated(); + systemSettings->updated(); //emit ConfigurationChanged(); } @@ -170,8 +170,6 @@ void VehicleConfig::setMixerType(UAVDataObject* mixer, int channel, MixerTypeEle if (mixerType >= 0 && mixerType < mixerTypeDescriptions.count()) { field->setValue(mixerTypeDescriptions[mixerType]); - // mixer->updated(); - qDebug()<<"updateMixer"; } } } @@ -219,7 +217,6 @@ void VehicleConfig::setMixerVectorValue(UAVDataObject* mixer, int channel, Mixer if (field) { field->setDouble(value, elementName); - //mixer->updated(); } } } From 1803f26e9a5af66cf1b1f3cdd1fa0907db82f2d4 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 14:01:33 -0500 Subject: [PATCH 077/543] Fix from hyper to catch when multiple object requests stack up --- ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp index ba65e84e5..d8f98be5c 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp @@ -388,6 +388,11 @@ void Telemetry::processObjectQueue() UAVObject::UpdateMode updateMode = UAVObject::GetGcsTelemetryUpdateMode(metadata); if ( ( objInfo.event != EV_UNPACKED ) && ( ( objInfo.event != EV_UPDATED_PERIODIC ) || ( updateMode != UAVObject::UPDATEMODE_THROTTLED ) ) ) { + QMap::iterator itr = transMap.find(objInfo.obj->getObjID()); + if ( itr != transMap.end() ) { + qDebug() << "!!!!!! Making request for an object: " << objInfo.obj->getName() << " for which a request is already in progress!!!!!!"; + return; + } UAVObject::Metadata metadata = objInfo.obj->getMetadata(); ObjectTransactionInfo *transInfo = new ObjectTransactionInfo(this); transInfo->obj = objInfo.obj; From 330fd26f4a549efe8fe653a420997c8bc551a7f9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 14:16:13 -0500 Subject: [PATCH 078/543] If we set FirmwareIAPObj to update on change then initial object retrieval will force it to be fetched before emitting the autopilotConnected signal. --- .../src/plugins/uavobjectutil/uavobjectutilmanager.cpp | 8 -------- shared/uavobjectdefinition/firmwareiapobj.xml | 2 +- 2 files changed, 1 insertion(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp index a30172fb0..be81befb7 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp @@ -247,14 +247,6 @@ FirmwareIAPObj::DataFields UAVObjectUtilManager::getFirmwareIap() if (!firmwareIap) return dummy; - // The code below will ask for the object update and wait for the updated to be received, - // or the timeout of the timer, set to 1 second. - QEventLoop loop; - connect(firmwareIap, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit())); - QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout - firmwareIap->requestUpdate(); - loop.exec(); - return firmwareIap->getData(); } diff --git a/shared/uavobjectdefinition/firmwareiapobj.xml b/shared/uavobjectdefinition/firmwareiapobj.xml index 30b070857..be8431ef5 100644 --- a/shared/uavobjectdefinition/firmwareiapobj.xml +++ b/shared/uavobjectdefinition/firmwareiapobj.xml @@ -10,7 +10,7 @@ - + From 9f1a8416f584c0311b5c3987c2d41b60f1ad91c0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 20:14:19 -0500 Subject: [PATCH 079/543] Treat the tricopter yaw channel like the other motor channels --- .../configmultirotorwidget.cpp | 342 +++++++++--------- 1 file changed, 169 insertions(+), 173 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index bfa4fe7a2..9953357ea 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -288,188 +288,183 @@ QStringList ConfigMultiRotorWidget::getChannelDescriptions() */ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets() { - QString airframeType; - QList motorList; + QString airframeType; + QList motorList; UAVDataObject* mixerObj = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(mixerObj); // Curve is also common to all quads: setThrottleCurve(mixerObj, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->multiThrottleCurve->getCurve() ); - - if (m_aircraft->multirotorFrameType->currentText() == "Quad +") { - airframeType = "QuadP"; - setupQuad(true); - } else if (m_aircraft->multirotorFrameType->currentText() == "Quad X") { - airframeType = "QuadX"; - setupQuad(false); - } else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter") { - airframeType = "Hexa"; - setupHexa(true); - } else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter X") { - airframeType = "HexaX"; - setupHexa(false); - } else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter Y6") { - airframeType = "HexaCoax"; - - //Show any config errors in GUI + + if (m_aircraft->multirotorFrameType->currentText() == "Quad +") { + airframeType = "QuadP"; + setupQuad(true); + } else if (m_aircraft->multirotorFrameType->currentText() == "Quad X") { + airframeType = "QuadX"; + setupQuad(false); + } else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter") { + airframeType = "Hexa"; + setupHexa(true); + } else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter X") { + airframeType = "HexaX"; + setupHexa(false); + } else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter Y6") { + airframeType = "HexaCoax"; + + //Show any config errors in GUI if (throwConfigError(6)) { - return airframeType; - } - motorList << "VTOLMotorNW" << "VTOLMotorW" << "VTOLMotorNE" << "VTOLMotorE" - << "VTOLMotorS" << "VTOLMotorSE"; - setupMotors(motorList); - - // Motor 1 to 6, Y6 Layout: - // pitch roll yaw - double mixer [8][3] = { - { 0.5, 1, -1}, - { 0.5, 1, 1}, - { 0.5, -1, -1}, - { 0.5, -1, 1}, - { -1, 0, -1}, - { -1, 0, 1}, - { 0, 0, 0}, - { 0, 0, 0} - }; - setupMultiRotorMixer(mixer); - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); - - } else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter") { - airframeType = "Octo"; - - //Show any config errors in GUI - if (throwConfigError(8)) { - return airframeType; + return airframeType; + } + motorList << "VTOLMotorNW" << "VTOLMotorW" << "VTOLMotorNE" << "VTOLMotorE" + << "VTOLMotorS" << "VTOLMotorSE"; + setupMotors(motorList); - } - motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE" - << "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW"; - setupMotors(motorList); - // Motor 1 to 8: - // pitch roll yaw - double mixer [8][3] = { - { 1, 0, -1}, - { 1, -1, 1}, - { 0, -1, -1}, - { -1, -1, 1}, - { -1, 0, -1}, - { -1, 1, 1}, - { 0, 1, -1}, - { 1, 1, 1} - }; - setupMultiRotorMixer(mixer); - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); - - } else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter V") { - airframeType = "OctoV"; - - //Show any config errors in GUI - if (throwConfigError(8)) { - return airframeType; - } - motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE" - << "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW"; - setupMotors(motorList); - // Motor 1 to 8: - // IMPORTANT: Assumes evenly spaced engines - // pitch roll yaw - double mixer [8][3] = { - { 0.33, -1, -1}, - { 1 , -1, 1}, - { -1 , -1, -1}, - { -0.33, -1, 1}, - { -0.33, 1, -1}, - { -1 , 1, 1}, - { 1 , 1, -1}, - { 0.33, 1, 1} - }; - setupMultiRotorMixer(mixer); - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); - - } else if (m_aircraft->multirotorFrameType->currentText() == "Octo Coax +") { - airframeType = "OctoCoaxP"; + // Motor 1 to 6, Y6 Layout: + // pitch roll yaw + double mixer [8][3] = { + { 0.5, 1, -1}, + { 0.5, 1, 1}, + { 0.5, -1, -1}, + { 0.5, -1, 1}, + { -1, 0, -1}, + { -1, 0, 1}, + { 0, 0, 0}, + { 0, 0, 0} + }; + setupMultiRotorMixer(mixer); + m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); - //Show any config errors in GUI - if (throwConfigError(8)) { - return airframeType; - } - motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE" - << "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW"; - setupMotors(motorList); - // Motor 1 to 8: - // pitch roll yaw - double mixer [8][3] = { - { 1, 0, -1}, - { 1, 0, 1}, - { 0, -1, -1}, - { 0, -1, 1}, - { -1, 0, -1}, - { -1, 0, 1}, - { 0, 1, -1}, - { 0, 1, 1} - }; - setupMultiRotorMixer(mixer); - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); - - } else if (m_aircraft->multirotorFrameType->currentText() == "Octo Coax X") { - airframeType = "OctoCoaxX"; - - //Show any config errors in GUI - if (throwConfigError(8)) { - return airframeType; - } - motorList << "VTOLMotorNW" << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" - << "VTOLMotorSE" << "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW"; - setupMotors(motorList); - // Motor 1 to 8: - // pitch roll yaw - double mixer [8][3] = { - { 1, 1, -1}, - { 1, 1, 1}, - { 1, -1, -1}, - { 1, -1, 1}, - { -1, -1, -1}, - { -1, -1, 1}, - { -1, 1, -1}, - { -1, 1, 1} - }; - setupMultiRotorMixer(mixer); - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); - - } else if (m_aircraft->multirotorFrameType->currentText() == "Tricopter Y") { - airframeType = "Tri"; + } else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter") { + airframeType = "Octo"; - //Show any config errors in GUI + //Show any config errors in GUI + if (throwConfigError(8)) { + return airframeType; + + } + motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE" + << "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW"; + setupMotors(motorList); + // Motor 1 to 8: + // pitch roll yaw + double mixer [8][3] = { + { 1, 0, -1}, + { 1, -1, 1}, + { 0, -1, -1}, + { -1, -1, 1}, + { -1, 0, -1}, + { -1, 1, 1}, + { 0, 1, -1}, + { 1, 1, 1} + }; + setupMultiRotorMixer(mixer); + m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + + } else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter V") { + airframeType = "OctoV"; + + //Show any config errors in GUI + if (throwConfigError(8)) { + return airframeType; + } + motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE" + << "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW"; + setupMotors(motorList); + // Motor 1 to 8: + // IMPORTANT: Assumes evenly spaced engines + // pitch roll yaw + double mixer [8][3] = { + { 0.33, -1, -1}, + { 1 , -1, 1}, + { -1 , -1, -1}, + { -0.33, -1, 1}, + { -0.33, 1, -1}, + { -1 , 1, 1}, + { 1 , 1, -1}, + { 0.33, 1, 1} + }; + setupMultiRotorMixer(mixer); + m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + + } else if (m_aircraft->multirotorFrameType->currentText() == "Octo Coax +") { + airframeType = "OctoCoaxP"; + + //Show any config errors in GUI + if (throwConfigError(8)) { + return airframeType; + } + motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE" + << "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW"; + setupMotors(motorList); + // Motor 1 to 8: + // pitch roll yaw + double mixer [8][3] = { + { 1, 0, -1}, + { 1, 0, 1}, + { 0, -1, -1}, + { 0, -1, 1}, + { -1, 0, -1}, + { -1, 0, 1}, + { 0, 1, -1}, + { 0, 1, 1} + }; + setupMultiRotorMixer(mixer); + m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + + } else if (m_aircraft->multirotorFrameType->currentText() == "Octo Coax X") { + airframeType = "OctoCoaxX"; + + //Show any config errors in GUI + if (throwConfigError(8)) { + return airframeType; + } + motorList << "VTOLMotorNW" << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" + << "VTOLMotorSE" << "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW"; + setupMotors(motorList); + // Motor 1 to 8: + // pitch roll yaw + double mixer [8][3] = { + { 1, 1, -1}, + { 1, 1, 1}, + { 1, -1, -1}, + { 1, -1, 1}, + { -1, -1, -1}, + { -1, -1, 1}, + { -1, 1, -1}, + { -1, 1, 1} + }; + setupMultiRotorMixer(mixer); + m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + + } else if (m_aircraft->multirotorFrameType->currentText() == "Tricopter Y") { + airframeType = "Tri"; + + //Show any config errors in GUI if (throwConfigError(3)) { - return airframeType; + return airframeType; - } - if (m_aircraft->triYawChannelBox->currentText() == "None") { - m_aircraft->mrStatusLabel->setText("Error: Assign a Yaw channel"); - return airframeType; - } - motorList << "VTOLMotorNW" << "VTOLMotorNE" << "VTOLMotorS"; - setupMotors(motorList); + } + if (m_aircraft->triYawChannelBox->currentText() == "None") { + m_aircraft->mrStatusLabel->setText("Error: Assign a Yaw channel"); + return airframeType; + } + motorList << "VTOLMotorNW" << "VTOLMotorNE" << "VTOLMotorS" << "" << "" << "" << "" << "" << "VTOLYaw"; + setupMotors(motorList); - GUIConfigDataUnion config = GetConfigData(); - config.multi.TRIYaw = m_aircraft->triYawChannelBox->currentIndex(); - SetConfigData(config); - - - // Motor 1 to 6, Y6 Layout: - // pitch roll yaw - double mixer [8][3] = { - { 0.5, 1, 0}, - { 0.5, -1, 0}, - { -1, 0, 0}, - { 0, 0, 0}, - { 0, 0, 0}, - { 0, 0, 0}, - { 0, 0, 0}, - { 0, 0, 0} - }; - setupMultiRotorMixer(mixer); + // Motor 1 to 6, Y6 Layout: + // pitch roll yaw + double mixer [8][3] = { + { 0.5, 1, 0}, + { 0.5, -1, 0}, + { -1, 0, 0}, + { 0, 0, 0}, + { 0, 0, 0}, + { 0, 0, 0}, + { 0, 0, 0}, + { 0, 0, 0} + }; + setupMultiRotorMixer(mixer); //tell the mixer about tricopter yaw channel @@ -719,13 +714,12 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) ); } - } else if (frameType == "Tri") { + } else if (frameType == "Tri") { // Motors 1 to 8 are N / NE / E / etc setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE); setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorS); - setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorS); setComboCurrentIndex(m_aircraft->triYawChannelBox,multi.TRIYaw); channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; @@ -771,8 +765,8 @@ void ConfigMultiRotorWidget::setupMotors(QList motorList) { QList mmList; mmList << m_aircraft->multiMotorChannelBox1 << m_aircraft->multiMotorChannelBox2 << m_aircraft->multiMotorChannelBox3 - << m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6 - << m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8; + << m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6 + << m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8 << m_aircraft->triYawChannelBox; GUIConfigDataUnion configData = GetConfigData(); ResetActuators(&configData); @@ -800,6 +794,8 @@ void ConfigMultiRotorWidget::setupMotors(QList motorList) configData.multi.VTOLMotorW = index; else if (motor == QString( "VTOLMotorNW")) configData.multi.VTOLMotorNW = index; + else if (motor == QString( "VTOLYaw" )) + configData.multi.TRIYaw = index; } SetConfigData(configData); From a75ed21012c8c225ffd1d78e71b0d8a088ca4f91 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 20:14:42 -0500 Subject: [PATCH 080/543] Fix tab indentation to be consistent with QT Creator --- .../configmultirotorwidget.cpp | 334 +++++++++--------- 1 file changed, 167 insertions(+), 167 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index 9953357ea..c9613e908 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -58,7 +58,7 @@ ConfigMultiRotorWidget::ConfigMultiRotorWidget(Ui_AircraftWidget *aircraft, QWid */ ConfigMultiRotorWidget::~ConfigMultiRotorWidget() { - // Do nothing + // Do nothing } @@ -86,13 +86,13 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) if (frameType == "Tri" || frameType == "Tricopter Y") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y")); - quad->setElementId("tri"); + quad->setElementId("tri"); - //Enable all necessary motor channel boxes... + //Enable all necessary motor channel boxes... for (i=1; i <=3; i++) { enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } - + } + m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); m_aircraft->mrYawMixLevel->setValue(50); @@ -102,132 +102,132 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) else if (frameType == "QuadX" || frameType == "Quad X") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X")); quad->setElementId("quad-x"); - - //Enable all necessary motor channel boxes... + + //Enable all necessary motor channel boxes... for (i=1; i <=4; i++) { enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + } // init mixer levels - m_aircraft->mrRollMixLevel->setValue(50); - m_aircraft->mrPitchMixLevel->setValue(50); - m_aircraft->mrYawMixLevel->setValue(50); + m_aircraft->mrRollMixLevel->setValue(50); + m_aircraft->mrPitchMixLevel->setValue(50); + m_aircraft->mrYawMixLevel->setValue(50); } else if (frameType == "QuadP" || frameType == "Quad +") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +")); - quad->setElementId("quad-plus"); - - //Enable all necessary motor channel boxes... + quad->setElementId("quad-plus"); + + //Enable all necessary motor channel boxes... for (i=1; i <=4; i++) { enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + } - m_aircraft->mrRollMixLevel->setValue(100); - m_aircraft->mrPitchMixLevel->setValue(100); - m_aircraft->mrYawMixLevel->setValue(50); + m_aircraft->mrRollMixLevel->setValue(100); + m_aircraft->mrPitchMixLevel->setValue(100); + m_aircraft->mrYawMixLevel->setValue(50); } else if (frameType == "Hexa" || frameType == "Hexacopter") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter")); - quad->setElementId("quad-hexa"); - - //Enable all necessary motor channel boxes... + quad->setElementId("quad-hexa"); + + //Enable all necessary motor channel boxes... for (i=1; i <=6; i++) { enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + } - m_aircraft->mrRollMixLevel->setValue(50); - m_aircraft->mrPitchMixLevel->setValue(33); - m_aircraft->mrYawMixLevel->setValue(33); + m_aircraft->mrRollMixLevel->setValue(50); + m_aircraft->mrPitchMixLevel->setValue(33); + m_aircraft->mrYawMixLevel->setValue(33); } else if (frameType == "HexaX" || frameType == "Hexacopter X" ) { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter X")); - quad->setElementId("quad-hexa-H"); - - //Enable all necessary motor channel boxes... + quad->setElementId("quad-hexa-H"); + + //Enable all necessary motor channel boxes... for (i=1; i <=6; i++) { enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + } + + m_aircraft->mrRollMixLevel->setValue(33); + m_aircraft->mrPitchMixLevel->setValue(50); + m_aircraft->mrYawMixLevel->setValue(33); - m_aircraft->mrRollMixLevel->setValue(33); - m_aircraft->mrPitchMixLevel->setValue(50); - m_aircraft->mrYawMixLevel->setValue(33); - } else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter Y6")); - quad->setElementId("hexa-coax"); - - //Enable all necessary motor channel boxes... + quad->setElementId("hexa-coax"); + + //Enable all necessary motor channel boxes... for (i=1; i <=6; i++) { enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + } + + m_aircraft->mrRollMixLevel->setValue(100); + m_aircraft->mrPitchMixLevel->setValue(50); + m_aircraft->mrYawMixLevel->setValue(66); - m_aircraft->mrRollMixLevel->setValue(100); - m_aircraft->mrPitchMixLevel->setValue(50); - m_aircraft->mrYawMixLevel->setValue(66); - } else if (frameType == "Octo" || frameType == "Octocopter") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter")); - quad->setElementId("quad-octo"); - - //Enable all necessary motor channel boxes + quad->setElementId("quad-octo"); + + //Enable all necessary motor channel boxes for (i=1; i <=8; i++) { enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + } - m_aircraft->mrRollMixLevel->setValue(33); - m_aircraft->mrPitchMixLevel->setValue(33); - m_aircraft->mrYawMixLevel->setValue(25); + m_aircraft->mrRollMixLevel->setValue(33); + m_aircraft->mrPitchMixLevel->setValue(33); + m_aircraft->mrYawMixLevel->setValue(25); } else if (frameType == "OctoV" || frameType == "Octocopter V") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter V")); - quad->setElementId("quad-octo-v"); + quad->setElementId("quad-octo-v"); - //Enable all necessary motor channel boxes + //Enable all necessary motor channel boxes for (i=1; i <=8; i++) { enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + } + + m_aircraft->mrRollMixLevel->setValue(25); + m_aircraft->mrPitchMixLevel->setValue(25); + m_aircraft->mrYawMixLevel->setValue(25); - m_aircraft->mrRollMixLevel->setValue(25); - m_aircraft->mrPitchMixLevel->setValue(25); - m_aircraft->mrYawMixLevel->setValue(25); - } else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +")); - quad->setElementId("octo-coax-P"); + quad->setElementId("octo-coax-P"); - //Enable all necessary motor channel boxes - for (int i=1; i <=8; i++) { + //Enable all necessary motor channel boxes + for (int i=1; i <=8; i++) { enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + } + + m_aircraft->mrRollMixLevel->setValue(100); + m_aircraft->mrPitchMixLevel->setValue(100); + m_aircraft->mrYawMixLevel->setValue(50); - m_aircraft->mrRollMixLevel->setValue(100); - m_aircraft->mrPitchMixLevel->setValue(100); - m_aircraft->mrYawMixLevel->setValue(50); - } else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X")); - quad->setElementId("octo-coax-X"); + quad->setElementId("octo-coax-X"); - //Enable all necessary motor channel boxes - for (int i=1; i <=8; i++) { + //Enable all necessary motor channel boxes + for (int i=1; i <=8; i++) { enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true); - } + } - m_aircraft->mrRollMixLevel->setValue(50); - m_aircraft->mrPitchMixLevel->setValue(50); - m_aircraft->mrYawMixLevel->setValue(50); - - } + m_aircraft->mrRollMixLevel->setValue(50); + m_aircraft->mrPitchMixLevel->setValue(50); + m_aircraft->mrYawMixLevel->setValue(50); + + } } void ConfigMultiRotorWidget::ResetActuators(GUIConfigDataUnion* configData) @@ -473,12 +473,12 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets() setMixerType(mixerObj, channel, VehicleConfig::MIXERTYPE_SERVO); setMixerVectorValue(mixerObj, channel, VehicleConfig::MIXERVECTOR_YAW, 127); } - - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); - + + m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + } - - return airframeType; + + return airframeType; } @@ -497,16 +497,16 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(mixer); - if (frameType == "QuadP") { + if (frameType == "QuadP") { // Motors 1/2/3/4 are: N / E / S / W setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN); setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorE); setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorS); setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorW); - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. + // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. + // This assumes that all vectors are identical - if not, the user should use the + // "custom" setting. channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; if (channel > -1) @@ -522,7 +522,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) m_aircraft->mrRollMixLevel->setValue( -value/1.27); } - } else if (frameType == "QuadX") { + } else if (frameType == "QuadX") { // Motors 1/2/3/4 are: NW / NE / SE / SW setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE); @@ -546,8 +546,8 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) } - } else if (frameType == "Hexa") { - // Motors 1/2/3 4/5/6 are: N / NE / SE / S / SW / NW + } else if (frameType == "Hexa") { + // Motors 1/2/3 4/5/6 are: N / NE / SE / S / SW / NW setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN); setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE); @@ -577,7 +577,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) } - } else if (frameType == "HexaX") { + } else if (frameType == "HexaX") { // Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNE); @@ -604,7 +604,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); m_aircraft->mrRollMixLevel->setValue( floor(1-value/1.27) ); } - } else if (frameType == "HexaCoax") { + } else if (frameType == "HexaCoax") { // Motors 1/2/3 4/5/6 are: NW/W NE/E S/SE setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW); @@ -630,8 +630,8 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); m_aircraft->mrRollMixLevel->setValue( value/1.27); } - } else if (frameType == "Octo" || frameType == "OctoV" || - frameType == "OctoCoaxP") { + } else if (frameType == "Octo" || frameType == "OctoV" || + frameType == "OctoCoaxP") { // Motors 1 to 8 are N / NE / E / etc setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN); @@ -687,7 +687,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) } } - } else if (frameType == "OctoCoaxX") { + } else if (frameType == "OctoCoaxX") { // Motors 1 to 8 are N / NE / E / etc setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW); @@ -732,7 +732,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) ); } - } + } } @@ -809,23 +809,23 @@ void ConfigMultiRotorWidget::setupMotors(QList motorList) bool ConfigMultiRotorWidget::setupQuad(bool pLayout) { // Check coherence: - - //Show any config errors in GUI + + //Show any config errors in GUI if (throwConfigError(4)) { - return false; + return false; } - - + + QList motorList; if (pLayout) { motorList << "VTOLMotorN" << "VTOLMotorE" << "VTOLMotorS" - << "VTOLMotorW"; + << "VTOLMotorW"; } else { motorList << "VTOLMotorNW" << "VTOLMotorNE" << "VTOLMotorSE" - << "VTOLMotorSW"; + << "VTOLMotorSW"; } setupMotors(motorList); - + // Now, setup the mixer: // Motor 1 to 4, X Layout: // pitch roll yaw @@ -834,15 +834,15 @@ bool ConfigMultiRotorWidget::setupQuad(bool pLayout) // {-0.5 ,-0.5 ,-0.5 //rear right motor (CW) // {-0.5 ,0.5 ,0.5 //Rear left motor (CCW) double xMixer [8][3] = { - { 1, 1, -1}, - { 1, -1, 1}, - {-1, -1, -1}, - {-1, 1, 1}, - { 0, 0, 0}, - { 0, 0, 0}, - { 0, 0, 0}, - { 0, 0, 0} - }; + { 1, 1, -1}, + { 1, -1, 1}, + {-1, -1, -1}, + {-1, 1, 1}, + { 0, 0, 0}, + { 0, 0, 0}, + { 0, 0, 0}, + { 0, 0, 0} + }; // // Motor 1 to 4, P Layout: // pitch roll yaw @@ -851,16 +851,16 @@ bool ConfigMultiRotorWidget::setupQuad(bool pLayout) // {-1 ,0 ,-0.5 //Rear motor (CW) // {0 ,1 ,0.5 //Left motor (CCW) double pMixer [8][3] = { - { 1, 0, -1}, - { 0, -1, 1}, - {-1, 0, -1}, - { 0, 1, 1}, - { 0, 0, 0}, - { 0, 0, 0}, - { 0, 0, 0}, - { 0, 0, 0} - }; - + { 1, 0, -1}, + { 0, -1, 1}, + {-1, 0, -1}, + { 0, 1, 1}, + { 0, 0, 0}, + { 0, 0, 0}, + { 0, 0, 0}, + { 0, 0, 0} + }; + if (pLayout) { setupMultiRotorMixer(pMixer); } else { @@ -878,22 +878,22 @@ bool ConfigMultiRotorWidget::setupQuad(bool pLayout) bool ConfigMultiRotorWidget::setupHexa(bool pLayout) { // Check coherence: - //Show any config errors in GUI + //Show any config errors in GUI if (throwConfigError(6)) - return false; + return false; QList motorList; if (pLayout) { motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorSE" - << "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorNW"; + << "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorNW"; } else { motorList << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE" - << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW"; + << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW"; } setupMotors(motorList); - + // and set only the relevant channels: - + // Motor 1 to 6, P Layout: // pitch roll yaw // 1 { 0.3 , 0 ,-0.3 // N CW @@ -902,8 +902,8 @@ bool ConfigMultiRotorWidget::setupHexa(bool pLayout) // 4 {-0.3 , 0 , 0.3 // S CCW // 5 {-0.3 , 0.5 ,-0.3 // SW CW // 6 { 0.3 , 0.5 , 0.3 // NW CCW - - double pMixer [8][3] = { + + double pMixer [8][3] = { { 1, 0, -1}, { 1, -1, 1}, {-1, -1, -1}, @@ -913,8 +913,8 @@ bool ConfigMultiRotorWidget::setupHexa(bool pLayout) { 0, 0, 0}, { 0, 0, 0} }; - - // + + // // Motor 1 to 6, X Layout: // 1 [ 0.5, -0.3, -0.3 ] NE // 2 [ 0 , -0.3, 0.3 ] E @@ -922,24 +922,24 @@ bool ConfigMultiRotorWidget::setupHexa(bool pLayout) // 4 [ -0.5, 0.3, 0.3 ] SW // 5 [ 0 , 0.3, -0.3 ] W // 6 [ 0.5, 0.3, 0.3 ] NW - double xMixer [8][3] = { - { 1, -1, -1}, - { 0, -1, 1}, - { -1, -1, -1}, - { -1, 1, 1}, - { 0, 1, -1}, - { 1, 1, 1}, - { 0, 0, 0}, - { 0, 0, 0} - }; - - if (pLayout) { - setupMultiRotorMixer(pMixer); - } else { - setupMultiRotorMixer(xMixer); - } - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); - return true; + double xMixer [8][3] = { + { 1, -1, -1}, + { 0, -1, 1}, + { -1, -1, -1}, + { -1, 1, 1}, + { 0, 1, -1}, + { 1, 1, 1}, + { 0, 0, 0}, + { 0, 0, 0} + }; + + if (pLayout) { + setupMultiRotorMixer(pMixer); + } else { + setupMultiRotorMixer(xMixer); + } + m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + return true; } @@ -960,8 +960,8 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3]) QList mmList; mmList << m_aircraft->multiMotorChannelBox1 << m_aircraft->multiMotorChannelBox2 << m_aircraft->multiMotorChannelBox3 - << m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6 - << m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8; + << m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6 + << m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8; UAVDataObject* mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(mixer); @@ -984,10 +984,10 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3]) int channel = mmList.at(i)->currentIndex()-1; if (channel > -1) setupQuadMotor(channel, mixerFactors[i][0]*pFactor, - rFactor*mixerFactors[i][1], yFactor*mixerFactors[i][2]); + rFactor*mixerFactors[i][1], yFactor*mixerFactors[i][2]); } } - // obj->updated(); + // obj->updated(); return true; } @@ -997,31 +997,31 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3]) */ bool ConfigMultiRotorWidget::throwConfigError(int numMotors) { - //Initialize configuration error flag - bool error=false; + //Initialize configuration error flag + bool error=false; - //Iterate through all instances of multiMotorChannelBox - for (int i=0; i(uiowner, "multiMotorChannelBox" + QString::number(i+1)); if (combobox){ if (combobox->currentText() == "None") { - int size = combobox->style()->pixelMetric(QStyle::PM_SmallIconSize); - QPixmap pixmap(size,size); - pixmap.fill(QColor("red")); + int size = combobox->style()->pixelMetric(QStyle::PM_SmallIconSize); + QPixmap pixmap(size,size); + pixmap.fill(QColor("red")); combobox->setItemData(0, pixmap, Qt::DecorationRole);//Set color palettes - error=true; - } - else { + error=true; + } + else { combobox->setItemData(0, 0, Qt::DecorationRole);//Reset color palettes - } - } - } - + } + } + } - if (error){ - m_aircraft->mrStatusLabel->setText(QString("ERROR: Assign all %1 motor channels").arg(numMotors)); - } + + if (error){ + m_aircraft->mrStatusLabel->setText(QString("ERROR: Assign all %1 motor channels").arg(numMotors)); + } return error; } From 150139b71142452166565525b7444a12778d3c1d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 20:38:50 -0500 Subject: [PATCH 081/543] Don't need to call updated() in the SetConfigData because the ConfigTaskWidget architecture will call that --- .../src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp index fe76f1660..0709f3652 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp @@ -105,7 +105,6 @@ void VehicleConfig::SetConfigData(GUIConfigDataUnion configData) { systemSettingsData.GUIConfigData[i] = configData.UAVObject[i]; systemSettings->setData(systemSettingsData); - systemSettings->updated(); //emit ConfigurationChanged(); } From 12192ae0cda926515c6b05bd0d8b1da9dd4d24a9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 20:40:11 -0500 Subject: [PATCH 082/543] Remove commented and debugging code --- .../cfg_vehicletypes/configmultirotorwidget.cpp | 17 ----------------- .../config/cfg_vehicletypes/vehicleconfig.cpp | 9 --------- 2 files changed, 26 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index c9613e908..eafa30fac 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -42,9 +42,6 @@ #include "actuatorsettings.h" #include "actuatorcommand.h" -//#define Pi 3.14159265358979323846 - - /** Constructor */ @@ -776,8 +773,6 @@ void ConfigMultiRotorWidget::setupMotors(QList motorList) index = mmList.takeFirst()->currentIndex(); - //qDebug()< mmList; mmList << m_aircraft->multiMotorChannelBox1 << m_aircraft->multiMotorChannelBox2 << m_aircraft->multiMotorChannelBox3 << m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6 @@ -977,7 +962,6 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3]) double pFactor = (double)m_aircraft->mrPitchMixLevel->value()/100; double rFactor = (double)m_aircraft->mrRollMixLevel->value()/100; double yFactor = (double)m_aircraft->mrYawMixLevel->value()/100; - qDebug()<isEnabled()) { @@ -987,7 +971,6 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3]) rFactor*mixerFactors[i][1], yFactor*mixerFactors[i][2]); } } - // obj->updated(); return true; } diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp index 0709f3652..8ae4c2588 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp @@ -44,11 +44,6 @@ VehicleConfig::VehicleConfig(QWidget *parent) : ConfigTaskWidget(parent) channelNames << QString("Channel%1").arg(i+1); } -// typedef enum { MIXERTYPE_DISABLED=0, MIXERTYPE_MOTOR=1, MIXERTYPE_SERVO=2, - //MIXERTYPE_CAMERAROLL=3, MIXERTYPE_CAMERAPITCH=4, MIXERTYPE_CAMERAYAW=5, - //MIXERTYPE_ACCESSORY0=6, MIXERTYPE_ACCESSORY1=7, MIXERTYPE_ACCESSORY2=8, - //MIXERTYPE_ACCESSORY3=9, MIXERTYPE_ACCESSORY4=10, MIXERTYPE_ACCESSORY5=11 } MixerTypeElem; - mixerTypeDescriptions << "Disabled" << "Motor" << "Servo" << "CameraRoll" << "CameraPitch" << "CameraYaw" << "Accessory0" << "Accessory1" << "Accessory2" << "Accessory3" << "Accessory4" << "Accessory5"; @@ -169,8 +164,6 @@ void VehicleConfig::setMixerType(UAVDataObject* mixer, int channel, MixerTypeEle { Q_ASSERT(mixer); - qDebug() << QString("setMixerType channel %0, type %1").arg(channel).arg(mixerType); - if (channel >= 0 && channel < mixerTypes.count()) { UAVObjectField *field = mixer->getField(mixerTypes.at(channel)); Q_ASSERT(field); @@ -218,8 +211,6 @@ void VehicleConfig::setMixerVectorValue(UAVDataObject* mixer, int channel, Mixer { Q_ASSERT(mixer); - qDebug() << QString("setMixerVectorValue channel %0, name %1, value %2").arg(channel).arg(elementName).arg(value); - if (channel >= 0 && channel < mixerVectors.count()) { UAVObjectField *field = mixer->getField(mixerVectors.at(channel)); Q_ASSERT(field); From 542483beecc8928764b5aeb012219588843ae7cc Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 20:44:34 -0500 Subject: [PATCH 083/543] Rephrase "SUCCESS: Mixer saved ok" to Configuration OK since it does not reflect if the save succeeded and the button does. --- .../configmultirotorwidget.cpp | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index eafa30fac..8568ba979 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -330,7 +330,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets() { 0, 0, 0} }; setupMultiRotorMixer(mixer); - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + m_aircraft->mrStatusLabel->setText(tr("Configuration OK")); } else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter") { airframeType = "Octo"; @@ -356,7 +356,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets() { 1, 1, 1} }; setupMultiRotorMixer(mixer); - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + m_aircraft->mrStatusLabel->setText(tr("Configuration OK")); } else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter V") { airframeType = "OctoV"; @@ -382,7 +382,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets() { 0.33, 1, 1} }; setupMultiRotorMixer(mixer); - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + m_aircraft->mrStatusLabel->setText(tr("Configuration OK")); } else if (m_aircraft->multirotorFrameType->currentText() == "Octo Coax +") { airframeType = "OctoCoaxP"; @@ -407,7 +407,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets() { 0, 1, 1} }; setupMultiRotorMixer(mixer); - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + m_aircraft->mrStatusLabel->setText(tr("Configuration OK")); } else if (m_aircraft->multirotorFrameType->currentText() == "Octo Coax X") { airframeType = "OctoCoaxX"; @@ -432,7 +432,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets() { -1, 1, 1} }; setupMultiRotorMixer(mixer); - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + m_aircraft->mrStatusLabel->setText(tr("Configuration OK")); } else if (m_aircraft->multirotorFrameType->currentText() == "Tricopter Y") { airframeType = "Tri"; @@ -443,7 +443,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets() } if (m_aircraft->triYawChannelBox->currentText() == "None") { - m_aircraft->mrStatusLabel->setText("Error: Assign a Yaw channel"); + m_aircraft->mrStatusLabel->setText(tr("Error: Assign a Yaw channel")); return airframeType; } motorList << "VTOLMotorNW" << "VTOLMotorNE" << "VTOLMotorS" << "" << "" << "" << "" << "" << "VTOLYaw"; @@ -471,7 +471,7 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets() setMixerVectorValue(mixerObj, channel, VehicleConfig::MIXERVECTOR_YAW, 127); } - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + m_aircraft->mrStatusLabel->setText(tr("Configuration OK")); } @@ -861,7 +861,7 @@ bool ConfigMultiRotorWidget::setupQuad(bool pLayout) } else { setupMultiRotorMixer(xMixer); } - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + m_aircraft->mrStatusLabel->setText(tr("Configuration OK")); return true; } @@ -933,7 +933,7 @@ bool ConfigMultiRotorWidget::setupHexa(bool pLayout) } else { setupMultiRotorMixer(xMixer); } - m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK"); + m_aircraft->mrStatusLabel->setText(tr("Configuration OK")); return true; } @@ -1003,7 +1003,7 @@ bool ConfigMultiRotorWidget::throwConfigError(int numMotors) if (error){ - m_aircraft->mrStatusLabel->setText(QString("ERROR: Assign all %1 motor channels").arg(numMotors)); + m_aircraft->mrStatusLabel->setText(QString(tr("ERROR: Assign all %1 motor channels")).arg(numMotors)); } return error; } From cddabf76cfdaa3bc1943c40564e0e9484907e506 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 20:50:22 -0500 Subject: [PATCH 084/543] Remove some debugging output that was a bit verbose --- .../plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index 8568ba979..cee5e8599 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -739,8 +739,6 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) */ void ConfigMultiRotorWidget::setupQuadMotor(int channel, double pitch, double roll, double yaw) { - qDebug()<(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(mixer); From bd3ebe5b6114727a0c37fe383f0688914058c5e6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 20:59:39 -0500 Subject: [PATCH 085/543] Undo the previous patch to abort transactions if one is pending, but throw a warning still --- ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp index d8f98be5c..1560980d0 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp @@ -391,7 +391,6 @@ void Telemetry::processObjectQueue() QMap::iterator itr = transMap.find(objInfo.obj->getObjID()); if ( itr != transMap.end() ) { qDebug() << "!!!!!! Making request for an object: " << objInfo.obj->getName() << " for which a request is already in progress!!!!!!"; - return; } UAVObject::Metadata metadata = objInfo.obj->getMetadata(); ObjectTransactionInfo *transInfo = new ObjectTransactionInfo(this); From eae94b218871eb6116c784a4c5cb76f981b3f90f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 28 Jul 2012 00:00:50 -0500 Subject: [PATCH 086/543] Use setField instead of setData in SetConfigData because that doesn't trigger a transaction immediately before the smartSaveButton tries to trigger one. --- .../plugins/config/cfg_vehicletypes/vehicleconfig.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp index 8ae4c2588..62adba243 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp @@ -95,13 +95,14 @@ void VehicleConfig::SetConfigData(GUIConfigDataUnion configData) { Q_ASSERT(systemSettings); SystemSettings::DataFields systemSettingsData = systemSettings->getData(); + UAVObjectField* guiConfig = systemSettings->getField("GUIConfigData"); + Q_ASSERT(guiConfig); + if(!guiConfig) + return; + // copy parameter configData -> systemsettings for (i = 0; i < (int)(SystemSettings::GUICONFIGDATA_NUMELEM); i++) - systemSettingsData.GUIConfigData[i] = configData.UAVObject[i]; - - systemSettings->setData(systemSettingsData); - - //emit ConfigurationChanged(); + guiConfig->setValue(configData.UAVObject[i], i); } void VehicleConfig::ResetActuators(GUIConfigDataUnion* configData) From 83ae672533969be0bfd8197a1f507fa635ba3e12 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Sat, 28 Jul 2012 17:26:43 +1000 Subject: [PATCH 087/543] Gonfig gadget now gets the whole of the screen. --- .../src/plugins/coreplugin/OpenPilotGCS.xml | 129 +++++++----------- 1 file changed, 46 insertions(+), 83 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml index d61dba982..490f9f85e 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml @@ -2,21 +2,11 @@ true true - LineardialGadget - Mainboard CPU + false + en_AU true - 476 - 697 + false - - - - 1 - 0 - - 1 - - 0 @@ -33,9 +23,39 @@ 87 100 - - 57600 - + + + + false + 1.0.0 + + + + + + + 0 + false + + 0 + 0 + 0 + + + + + + 0 + + 1 + + false + + 0 + + + + @@ -858,6 +878,7 @@ false false false + 0 2 1 0 @@ -1712,7 +1733,6 @@ false false - 1000 60 @@ -1758,7 +1778,6 @@ false false - 1000 20 @@ -1814,7 +1833,6 @@ false false - 1000 60 @@ -1860,7 +1878,6 @@ false false - 1000 60 @@ -1886,7 +1903,6 @@ false false - 1000 40 @@ -1982,7 +1998,6 @@ false false - 1000 60 @@ -2028,7 +2043,6 @@ false false - 1000 60 @@ -2074,7 +2088,6 @@ false false - 1000 60 @@ -2120,7 +2133,6 @@ false false - 1000 240 @@ -2256,7 +2268,6 @@ false false - 1000 20 @@ -2302,7 +2313,6 @@ false false - 1000 240 @@ -2317,9 +2327,6 @@ 0 - - - 0 1 0 @@ -2349,9 +2356,13 @@ 0.0.0 + false + false #5baa56 + false #ff7957 500 + false @@ -2631,59 +2642,11 @@ false - - - ConfigGadget - - default - - uavGadget - - - - LineardialGadget - - Telemetry RX Rate Horizontal - - uavGadget - - - LineardialGadget - - Telemetry TX Rate Horizontal - - uavGadget - - 1 - @Variant(AAAACQAAAAA=) - splitter - - 2 - @Variant(AAAACQAAAAIAAAACAAACNQAAAAIAAABC) - splitter - - - - UAVObjectBrowser - - default - - uavGadget - - - GCSControlGadget - - MS Sidewinder - - uavGadget - - 2 - @Variant(AAAACQAAAAIAAAACAAABqgAAAAIAAAFi) - splitter - - 1 - @Variant(AAAACQAAAAIAAAACAAAC3gAAAAIAAAJ3) - splitter + ConfigGadget + + default + + uavGadget UAVGadgetManagerV1 From 999e5e9cc5e531e17cafe480388416f76a82efcf Mon Sep 17 00:00:00 2001 From: Dmytro Poplavskiy Date: Sat, 28 Jul 2012 21:00:02 +1000 Subject: [PATCH 088/543] Fixed uninitialized terrainEnabled property --- ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp index ac2d7ada2..40c748239 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp @@ -32,7 +32,8 @@ #include PfdQmlGadgetWidget::PfdQmlGadgetWidget(QWidget *parent) : - QDeclarativeView(parent) + QDeclarativeView(parent), + m_terrainEnabled(false) { setMinimumSize(64,64); setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); From dc4254d7d88c63c638378c78405381cfbb7efc5e Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sat, 28 Jul 2012 15:04:55 +0100 Subject: [PATCH 089/543] GCS-Several UI fixes according to beta testers reports. --- .../src/plugins/config/camerastabilization.ui | 6 +- .../src/plugins/config/stabilization.ui | 265 ++---------------- .../importsummarydialog.ui | 2 +- 3 files changed, 21 insertions(+), 252 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index 116bab28a..098080ce6 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -131,8 +131,8 @@ 0 0 - 790 - 648 + 792 + 630 @@ -176,7 +176,7 @@ - After enabling the module, you must power cycle before using and configuring. + After configuring you must power cycle your board before using and configuring diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 57b250731..97434d7f1 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -600,47 +600,14 @@ 0 0 - 756 - 817 + 758 + 806 - -1 + 6 - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - - - - - 0 - 16 - - - - Rate Stabilization (Inner Loop) - - - - - @@ -662,14 +629,14 @@ - + Rate Stabilization (Inner Loop) Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - -1 + 6 @@ -3538,39 +3505,6 @@ value as the Kp. - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 20 - 13 - - - - - - - - - 0 - 16 - - - - Attitude Stabilization (Outer Loop) - - - - - @@ -4109,7 +4043,7 @@ value as the Kp. false - + Attitude Stabilization (Outer Loop) Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -6905,39 +6839,6 @@ border-radius: 5; - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 20 - 13 - - - - - - - - - 0 - 16 - - - - Stick Range and Limits - - - - - @@ -7473,7 +7374,7 @@ border-radius: 5; - + Stick Range and Limits Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -10744,8 +10645,8 @@ automatically every 300ms, which will help for fast tuning. 0 0 - 470 - 914 + 758 + 806 @@ -10753,41 +10654,8 @@ automatically every 300ms, which will help for fast tuning. - -1 + 6 - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - - - - - 241 - 16 - - - - Rate Stabization Coefficients (Inner Loop) - - - - - @@ -11323,7 +11191,7 @@ automatically every 300ms, which will help for fast tuning. - + Rate Stabization Coefficients (Inner Loop) Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -14246,39 +14114,6 @@ value as the Kp. - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - - - - - 241 - 16 - - - - Attitude Stabization Coefficients (Outer Loop) - - - - - @@ -14817,7 +14652,7 @@ value as the Kp. false - + Attitude Stabization Coefficients (Outer Loop) Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -14829,7 +14664,7 @@ value as the Kp. - -1 + 6 @@ -17545,39 +17380,6 @@ border-radius: 5; - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - - - - - 180 - 16 - - - - Stick Range and Limits - - - - - @@ -18113,7 +17915,7 @@ border-radius: 5; - + Stick Range and Limits Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -18122,7 +17924,7 @@ border-radius: 5; - -1 + 6 @@ -20864,39 +20666,6 @@ rate(deg/s) - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - - - - - 180 - 16 - - - - Sensor Tunning - - - - - @@ -21429,7 +21198,7 @@ rate(deg/s) false - + Sensor Tuning Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -21438,7 +21207,7 @@ rate(deg/s) - -1 + 6 diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/importsummarydialog.ui b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/importsummarydialog.ui index 7c7212eb0..20873ae4b 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/importsummarydialog.ui +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/importsummarydialog.ui @@ -101,7 +101,7 @@ then close the dialog. - Save to Board Flash/SD + Save to Board Flash From fef831ec2bbc3083844f592fdbc149a8c4047c8a Mon Sep 17 00:00:00 2001 From: David Ankers Date: Sun, 29 Jul 2012 01:53:45 +1000 Subject: [PATCH 090/543] Add stylesheets and ensure they are copied on build --- ground/openpilotgcs/src/app/app.pro | 7 +++++-- ground/openpilotgcs/src/app/stylesheets/linux.qss | 0 ground/openpilotgcs/src/app/stylesheets/macos.qss | 0 ground/openpilotgcs/src/app/stylesheets/windows.qss | 0 4 files changed, 5 insertions(+), 2 deletions(-) create mode 100644 ground/openpilotgcs/src/app/stylesheets/linux.qss create mode 100644 ground/openpilotgcs/src/app/stylesheets/macos.qss create mode 100644 ground/openpilotgcs/src/app/stylesheets/windows.qss diff --git a/ground/openpilotgcs/src/app/app.pro b/ground/openpilotgcs/src/app/app.pro index c644f7c97..e66f3f4f0 100644 --- a/ground/openpilotgcs/src/app/app.pro +++ b/ground/openpilotgcs/src/app/app.pro @@ -14,8 +14,6 @@ include(../libs/utils/utils.pri) LIBS *= -l$$qtLibraryName(ExtensionSystem) -l$$qtLibraryName(Aggregation) win32 { -# CONFIG(debug, debug|release):LIBS *= -lExtensionSystemd -lAggregationd -lQExtSerialPortd -# else:LIBS *= -lExtensionSystem -lAggregation -lQExtSerialPort RC_FILE = openpilotgcs.rc target.path = /bin INSTALLS += target @@ -32,3 +30,8 @@ win32 { } OTHER_FILES += openpilotgcs.rc + +style_copy.commands += $(COPY_FILE) $$targetPath(\"$$GCS_SOURCE_TREE/src/app/stylesheets/*.qss\") $$targetPath(\"$$GCS_APP_PATH\") $$addNewline() +style_copy.target = FORCE +QMAKE_EXTRA_TARGETS += style_copy + diff --git a/ground/openpilotgcs/src/app/stylesheets/linux.qss b/ground/openpilotgcs/src/app/stylesheets/linux.qss new file mode 100644 index 000000000..e69de29bb diff --git a/ground/openpilotgcs/src/app/stylesheets/macos.qss b/ground/openpilotgcs/src/app/stylesheets/macos.qss new file mode 100644 index 000000000..e69de29bb diff --git a/ground/openpilotgcs/src/app/stylesheets/windows.qss b/ground/openpilotgcs/src/app/stylesheets/windows.qss new file mode 100644 index 000000000..e69de29bb From 1fca385fc4478342a8d211e747a52e186f384889 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Sun, 29 Jul 2012 03:00:17 +1000 Subject: [PATCH 091/543] Change RPY to Roll,Pitch and Yaw for the mixer on the aircraft screen, as per mikes suggestion --- .../src/plugins/config/airframe.ui | 26 +++++++++---------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index a9de06541..6e61303e4 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -119,8 +119,8 @@ 0 0 - 779 - 691 + 785 + 703 @@ -802,7 +802,7 @@ font: bold 12px; margin:1px; - R + Roll Qt::AlignCenter @@ -862,7 +862,7 @@ font: bold 12px; margin:1px; - P + Pitch Qt::AlignCenter @@ -928,7 +928,7 @@ font: bold 12px; margin:1px; - Y + Yaw Qt::AlignCenter @@ -1017,7 +1017,6 @@ margin:1px; background:transparent - @@ -2756,8 +2755,8 @@ margin:1px; 0 0 - 779 - 679 + 192 + 236 @@ -3068,14 +3067,15 @@ p, li { white-space: pre-wrap; } <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;"> +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> <table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;"> <tr> <td style="border: none;"> <p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD REQUIRES CAUTION</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</p> -<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</p></td></tr></table></body></html> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;"><br /></span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</span></p> +<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</span></p></td></tr></table></body></html> @@ -3084,7 +3084,7 @@ p, li { white-space: pre-wrap; } - + From 9395df6d2dad306c721b5460836472eb549e41de Mon Sep 17 00:00:00 2001 From: David Ankers Date: Sun, 29 Jul 2012 03:27:51 +1000 Subject: [PATCH 092/543] Make size of labels consistant --- .../src/plugins/config/camerastabilization.ui | 78 ++++++++++++++++++- 1 file changed, 75 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index 098080ce6..ff1f84049 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -131,8 +131,8 @@ 0 0 - 792 - 630 + 790 + 644 @@ -176,7 +176,7 @@ - After configuring you must power cycle your board before using and configuring + After enabling you must power cycle your board before using and configuring @@ -328,6 +328,18 @@ have to define channel output range using Output configuration tab. + + + 0 + 0 + + + + + 0 + 16 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -345,6 +357,18 @@ margin:1px; + + + 0 + 0 + + + + + 0 + 16 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -362,6 +386,18 @@ margin:1px; + + + 0 + 0 + + + + + 0 + 16 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -432,6 +468,18 @@ margin:1px; + + + 0 + 0 + + + + + 0 + 16 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -449,6 +497,18 @@ margin:1px; + + + 0 + 0 + + + + + 0 + 16 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -466,6 +526,18 @@ margin:1px; + + + 0 + 0 + + + + + 0 + 16 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); From 5f8c6dc7afb75c3081ac04e06e7293efd8c509bc Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sat, 28 Jul 2012 19:06:54 +0100 Subject: [PATCH 093/543] Remove unwanted file --- .../notify/notifypluginoptionspage.cpp.orig | 512 ------------------ 1 file changed, 512 deletions(-) delete mode 100644 ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp.orig diff --git a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp.orig b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp.orig deleted file mode 100644 index 2ff775e31..000000000 --- a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp.orig +++ /dev/null @@ -1,512 +0,0 @@ -/** - ****************************************************************************** - * - * @file notifypluginoptionspage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Notify Plugin options page - * @see The GNU Public License (GPL) Version 3 - * @defgroup notifyplugin - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "notifypluginoptionspage.h" -#include -#include "notificationitem.h" -#include "ui_notifypluginoptionspage.h" -#include "extensionsystem/pluginmanager.h" -#include "utils/pathutils.h" - -#include -#include -#include -#include -#include -#include -#include - -#include "notifyplugin.h" -#include "notifyitemdelegate.h" -#include "notifytablemodel.h" -#include "notifylogging.h" - -NotifyPluginOptionsPage::NotifyPluginOptionsPage(/*NotificationItem *config,*/ QObject *parent) - : IOptionsPage(parent) - , objManager(*ExtensionSystem::PluginManager::instance()->getObject()) - , owner(qobject_cast(parent)) - , currentCollectionPath("") -{ -} - -NotifyPluginOptionsPage::~NotifyPluginOptionsPage() -{ -} - -//creates options page widget (uses the UI file) -QWidget *NotifyPluginOptionsPage::createPage(QWidget *parent) -{ - options_page.reset(new Ui::NotifyPluginOptionsPage()); - //main widget - QWidget *optionsPageWidget = new QWidget; - //main layout - options_page->setupUi(optionsPageWidget); - - listSoundFiles.clear(); - - options_page->SoundDirectoryPathChooser->setExpectedKind(Utils::PathChooser::Directory); - options_page->SoundDirectoryPathChooser->setPromptDialogTitle(tr("Choose sound collection directory")); - - // Fills the combo boxes for the UAVObjects - QList< QList > objList = objManager.getDataObjects(); - foreach (QList list, objList) { - foreach (UAVDataObject* obj, list) { - options_page->UAVObject->addItem(obj->getName()); - } - } - -<<<<<<< Updated upstream - connect(options_page->SoundDirectoryPathChooser, SIGNAL(changed(const QString&)), this, SLOT(on_buttonSoundFolder_clicked(const QString&))); - connect(options_page->SoundCollectionList, SIGNAL(currentIndexChanged (int)), this, SLOT(on_soundLanguage_indexChanged(int))); - connect(options_page->UAVObject, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_UAVObject_indexChanged(QString))); -======= - options_page = new Ui::NotifyPluginOptionsPage(); - //main widget - QWidget *optionsPageWidget = new QWidget; - //main layout - options_page->setupUi(optionsPageWidget); - - delegateItems.clear(); - listSoundFiles.clear(); - - options_page->horizontalLayout_3->addWidget(new QPushButton("testtt")); - delegateItems << "Repeat Once" - << "Repeat Instantly" - << "Repeat 10 seconds" - << "Repeat 30 seconds" - << "Repeat 1 minute"; - - options_page->chkEnableSound->setChecked(owner->getEnableSound()); - options_page->SoundDirectoryPathChooser->setExpectedKind(Utils::PathChooser::Directory); - options_page->SoundDirectoryPathChooser->setPromptDialogTitle(tr("Choose sound collection directory")); - - - - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - objManager = pm->getObject(); - - // Fills the combo boxes for the UAVObjects - QList< QList > objList = objManager->getDataObjects(); - foreach (QList list, objList) { - foreach (UAVDataObject* obj, list) { - options_page->UAVObject->addItem(obj->getName()); - } - } - - connect(options_page->SoundDirectoryPathChooser, SIGNAL(changed(const QString&)), this, SLOT(on_buttonSoundFolder_clicked(const QString&))); - connect(options_page->SoundCollectionList, SIGNAL(currentIndexChanged (int)), this, SLOT(on_soundLanguage_indexChanged(int))); - connect(options_page->buttonAdd, SIGNAL(pressed()), this, SLOT(on_buttonAddNotification_clicked())); - connect(options_page->buttonDelete, SIGNAL(pressed()), this, SLOT(on_buttonDeleteNotification_clicked())); - connect(options_page->buttonModify, SIGNAL(pressed()), this, SLOT(on_buttonModifyNotification_clicked())); -// connect(options_page->buttonTestSound1, SIGNAL(clicked()), this, SLOT(on_buttonTestSound1_clicked())); -// connect(options_page->buttonTestSound2, SIGNAL(clicked()), this, SLOT(on_buttonTestSound2_clicked())); - connect(options_page->buttonPlayNotification, SIGNAL(clicked()), this, SLOT(on_buttonTestSoundNotification_clicked())); - connect(options_page->chkEnableSound, SIGNAL(toggled(bool)), this, SLOT(on_chkEnableSound_toggled(bool))); - - - connect(options_page->UAVObject, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_UAVObject_indexChanged(QString))); - connect(this, SIGNAL(updateNotifications(QList)), - owner, SLOT(updateNotificationList(QList))); - connect(this, SIGNAL(resetNotification()),owner, SLOT(resetNotification())); - - //emit resetNotification(); - - - privListNotifications.clear(); - - for (int i = 0; i < owner->getListNotifications().size(); ++i) { - NotifyPluginConfiguration* notification = new NotifyPluginConfiguration(); - owner->getListNotifications().at(i)->copyTo(notification); - privListNotifications.append(notification); - } - - updateConfigView(owner->getCurrentNotification()); - - options_page->chkEnableSound->setChecked(owner->getEnableSound()); - - QStringList headerStrings; - headerStrings << "Name" << "Repeats" << "Lifetime,sec"; ->>>>>>> Stashed changes - - connect(this, SIGNAL(updateNotifications(QList)), - owner, SLOT(updateNotificationList(QList))); - //connect(this, SIGNAL(resetNotification()),owner, SLOT(resetNotification())); - - -// privListNotifications = ((qobject_cast(parent))->getListNotifications()); - privListNotifications = owner->getListNotifications(); - - updateConfigView(owner->getCurrentNotification()); - - initRulesTable(); - initButtons(); - initPhononPlayer(); - - return optionsPageWidget; -} - -void NotifyPluginOptionsPage::initButtons() -{ - options_page->chkEnableSound->setChecked(owner->getEnableSound()); - connect(options_page->chkEnableSound, SIGNAL(toggled(bool)), this, SLOT(on_chkEnableSound_toggled(bool))); - - options_page->buttonModify->setEnabled(false); - options_page->buttonDelete->setEnabled(false); - options_page->buttonPlayNotification->setEnabled(false); - connect(options_page->buttonAdd, SIGNAL(pressed()), this, SLOT(on_buttonAddNotification_clicked())); - connect(options_page->buttonDelete, SIGNAL(pressed()), this, SLOT(on_buttonDeleteNotification_clicked())); - connect(options_page->buttonModify, SIGNAL(pressed()), this, SLOT(on_buttonModifyNotification_clicked())); - connect(options_page->buttonPlayNotification, SIGNAL(clicked()), this, SLOT(on_buttonTestSoundNotification_clicked())); -} - -void NotifyPluginOptionsPage::initPhononPlayer() -{ - notifySound.reset(Phonon::createPlayer(Phonon::NotificationCategory)); - connect(notifySound.data(),SIGNAL(stateChanged(Phonon::State,Phonon::State)), - this,SLOT(changeButtonText(Phonon::State,Phonon::State))); - connect(notifySound.data(), SIGNAL(finished(void)), this, SLOT(onFinishedPlaying(void))); -} - -void NotifyPluginOptionsPage::initRulesTable() -{ - qNotifyDebug_if(_notifyRulesModel.isNull()) << "_notifyRulesModel.isNull())"; - qNotifyDebug_if(!_notifyRulesSelection) << "_notifyRulesSelection.isNull())"; - //QItemSelectionModel* selection = _notifyRulesSelection.take(); - _notifyRulesModel.reset(new NotifyTableModel(privListNotifications)); - _notifyRulesSelection = new QItemSelectionModel(_notifyRulesModel.data()); - - connect(_notifyRulesSelection, SIGNAL(selectionChanged ( const QItemSelection &, const QItemSelection & )), - this, SLOT(on_tableNotification_changeSelection( const QItemSelection & , const QItemSelection & ))); - connect(this, SIGNAL(entryUpdated(int)), - _notifyRulesModel.data(), SLOT(entryUpdated(int))); - connect(this, SIGNAL(entryAdded(int)), - _notifyRulesModel.data(), SLOT(entryAdded(int))); - - options_page->notifyRulesView->setModel(_notifyRulesModel.data()); - options_page->notifyRulesView->setSelectionModel(_notifyRulesSelection); - options_page->notifyRulesView->setItemDelegate(new NotifyItemDelegate(this)); - - options_page->notifyRulesView->resizeRowsToContents(); - options_page->notifyRulesView->setColumnWidth(eMESSAGE_NAME,200); - options_page->notifyRulesView->setColumnWidth(eREPEAT_VALUE,120); - options_page->notifyRulesView->setColumnWidth(eEXPIRE_TIME,100); - options_page->notifyRulesView->setColumnWidth(eENABLE_NOTIFICATION,60); - options_page->notifyRulesView->setDragEnabled(true); - options_page->notifyRulesView->setAcceptDrops(true); - options_page->notifyRulesView->setDropIndicatorShown(true); - options_page->notifyRulesView->setDragDropMode(QAbstractItemView::InternalMove); - - -} - -void NotifyPluginOptionsPage::getOptionsPageValues(NotificationItem* notification) -{ - notification->setSoundCollectionPath(options_page->SoundDirectoryPathChooser->path()); - notification->setCurrentLanguage(options_page->SoundCollectionList->currentText()); - notification->setDataObject(options_page->UAVObject->currentText()); - notification->setObjectField(options_page->UAVObjectField->currentText()); - notification->setSound1(options_page->Sound1->currentText()); - notification->setSound2(options_page->Sound2->currentText()); - notification->setSound3(options_page->Sound3->currentText()); - notification->setSayOrder(options_page->SayOrder->currentText()); - notification->setValue(options_page->Value->currentText()); - notification->setSpinBoxValue(options_page->ValueSpinBox->value()); -} - -/*! -* Called when the user presses apply or OK. -* Saves the current values -*/ -void NotifyPluginOptionsPage::apply() -{ - getOptionsPageValues(owner->getCurrentNotification()); - owner->setEnableSound(options_page->chkEnableSound->isChecked()); - emit updateNotifications(privListNotifications); -} - -void NotifyPluginOptionsPage::finish() -{ - disconnect(notifySound.data(),SIGNAL(stateChanged(Phonon::State,Phonon::State)), - this,SLOT(changeButtonText(Phonon::State,Phonon::State))); - if (notifySound) { - notifySound->stop(); - notifySound->clear(); - } -} - -////////////////////////////////////////////////////////////////////////////// -// Fills in the combo box when value is changed in the -// combo box -////////////////////////////////////////////////////////////////////////////// -void NotifyPluginOptionsPage::on_UAVObject_indexChanged(QString val) { - options_page->UAVObjectField->clear(); - ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager* objManager = pm->getObject(); - UAVDataObject* obj = dynamic_cast( objManager->getObject(val) ); - QList fieldList = obj->getFields(); - foreach (UAVObjectField* field, fieldList) { - options_page->UAVObjectField->addItem(field->getName()); - } -} - -// locate collection folder on disk -void NotifyPluginOptionsPage::on_buttonSoundFolder_clicked(const QString& path) -{ - QDir dirPath(path); - listDirCollections = dirPath.entryList(QDir::AllDirs | QDir::NoDotAndDotDot); - options_page->SoundCollectionList->clear(); - options_page->SoundCollectionList->addItems(listDirCollections); -} - - -void NotifyPluginOptionsPage::on_soundLanguage_indexChanged(int index) -{ - options_page->SoundCollectionList->setCurrentIndex(index); - - currentCollectionPath = options_page->SoundDirectoryPathChooser->path() - + QDir::toNativeSeparators("/" + options_page->SoundCollectionList->currentText()); - - QDir dirPath(currentCollectionPath); - QStringList filters; - filters << "*.mp3" << "*.wav"; - dirPath.setNameFilters(filters); - listSoundFiles = dirPath.entryList(filters); - listSoundFiles.replaceInStrings(QRegExp(".mp3|.wav"), ""); - options_page->Sound1->clear(); - options_page->Sound2->clear(); - options_page->Sound3->clear(); - options_page->Sound1->addItems(listSoundFiles); - options_page->Sound2->addItem(""); - options_page->Sound2->addItems(listSoundFiles); - options_page->Sound3->addItem(""); - options_page->Sound3->addItems(listSoundFiles); - -} - -void NotifyPluginOptionsPage::changeButtonText(Phonon::State newstate, Phonon::State oldstate) -{ - //Q_ASSERT(Phonon::ErrorState != newstate); - - if (newstate == Phonon::PausedState || newstate == Phonon::StoppedState) { - options_page->buttonPlayNotification->setText("Play"); - options_page->buttonPlayNotification->setIcon(QPixmap(":/notify/images/play.png")); - } else { - if (newstate == Phonon::PlayingState) { - options_page->buttonPlayNotification->setText("Stop"); - options_page->buttonPlayNotification->setIcon(QPixmap(":/notify/images/stop.png")); - } - } -} - -void NotifyPluginOptionsPage::onFinishedPlaying() -{ - notifySound->clear(); -} - -void NotifyPluginOptionsPage::on_buttonTestSoundNotification_clicked() -{ - NotificationItem* notification = NULL; - - if (-1 == _notifyRulesSelection->currentIndex().row()) - return; - notifySound->clearQueue(); - notification = privListNotifications.at(_notifyRulesSelection->currentIndex().row()); - notification->parseNotifyMessage(); - QStringList sequence = notification->getMessageSequence(); - Q_ASSERT(!!sequence.size()); - foreach(QString item, sequence) - notifySound->enqueue(Phonon::MediaSource(item)); - - notifySound->play(); -} - -void NotifyPluginOptionsPage::on_chkEnableSound_toggled(bool state) -{ - bool state1 = 1^state; - - QList listOutputs = notifySound->outputPaths(); - Phonon::AudioOutput * audioOutput = (Phonon::AudioOutput*)listOutputs.last().sink(); - audioOutput->setMuted(state1); -} - -void NotifyPluginOptionsPage::updateConfigView(NotificationItem* notification) -{ - QString path = notification->getSoundCollectionPath(); - if (path == "") { - //QDir dir = QDir::currentPath(); - //path = QDir::currentPath().left(QDir::currentPath().indexOf("OpenPilot",0,Qt::CaseSensitive))+"../share/sounds"; - path = Utils::PathUtils().InsertDataPath("%%DATAPATH%%sounds"); - } - - options_page->SoundDirectoryPathChooser->setPath(path); - - if (-1 != options_page->SoundCollectionList->findText(notification->getCurrentLanguage())){ - options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText(notification->getCurrentLanguage())); - } else { - options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default")); - } - - if (options_page->UAVObject->findText(notification->getDataObject())!=-1){ - options_page->UAVObject->setCurrentIndex(options_page->UAVObject->findText(notification->getDataObject())); - } - - // Now load the object field values: - options_page->UAVObjectField->clear(); - QString uavDataObject = notification->getDataObject(); - UAVDataObject* obj = dynamic_cast(objManager.getObject(uavDataObject)); - if (obj != NULL ) { - QList fieldList = obj->getFields(); - foreach (UAVObjectField* field, fieldList) { - options_page->UAVObjectField->addItem(field->getName()); - } - } - - if (-1 != options_page->UAVObjectField->findText(notification->getObjectField())) { - options_page->UAVObjectField->setCurrentIndex(options_page->UAVObjectField->findText(notification->getObjectField())); - } - - if (-1 != options_page->Sound1->findText(notification->getSound1())) { - options_page->Sound1->setCurrentIndex(options_page->Sound1->findText(notification->getSound1())); - } else { - // show item from default location - options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default")); - options_page->Sound1->setCurrentIndex(options_page->Sound1->findText(notification->getSound1())); - - // don't show item if it wasn't find in stored location - //options_page->Sound1->setCurrentIndex(-1); - } - - if (-1 != options_page->Sound2->findText(notification->getSound2())) { - options_page->Sound2->setCurrentIndex(options_page->Sound2->findText(notification->getSound2())); - } else { - // show item from default location - options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default")); - options_page->Sound2->setCurrentIndex(options_page->Sound2->findText(notification->getSound2())); - - // don't show item if it wasn't find in stored location - //options_page->Sound2->setCurrentIndex(-1); - } - - if (-1 != options_page->Sound3->findText(notification->getSound3())) { - options_page->Sound3->setCurrentIndex(options_page->Sound3->findText(notification->getSound3())); - } else { - // show item from default location - options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default")); - options_page->Sound3->setCurrentIndex(options_page->Sound3->findText(notification->getSound3())); - } - - if (-1 != options_page->Value->findText(notification->getValue())) { - options_page->Value->setCurrentIndex(options_page->Value->findText(notification->getValue())); - } - - if (-1 != options_page->SayOrder->findText(notification->getSayOrder())) { - options_page->SayOrder->setCurrentIndex(options_page->SayOrder->findText(notification->getSayOrder())); - } - - options_page->ValueSpinBox->setValue(notification->getSpinBoxValue()); -} - -void NotifyPluginOptionsPage::on_tableNotification_changeSelection( const QItemSelection & selected, const QItemSelection & deselected ) -{ - bool select = false; - notifySound->stop(); - if (selected.indexes().size()) { - select = true; - updateConfigView(privListNotifications.at(selected.indexes().at(0).row())); - } - - options_page->buttonModify->setEnabled(select); - options_page->buttonDelete->setEnabled(select); - options_page->buttonPlayNotification->setEnabled(select); -} - - -void NotifyPluginOptionsPage::on_buttonAddNotification_clicked() -{ - NotificationItem* notification = new NotificationItem; - - if (options_page->SoundDirectoryPathChooser->path()=="") { - QPalette textPalette=options_page->SoundDirectoryPathChooser->palette(); - textPalette.setColor(QPalette::Normal,QPalette::Text, Qt::red); - options_page->SoundDirectoryPathChooser->setPalette(textPalette); - options_page->SoundDirectoryPathChooser->setPath("please select sound collection folder"); - return; - } - - notification->setSoundCollectionPath(options_page->SoundDirectoryPathChooser->path()); - notification->setCurrentLanguage(options_page->SoundCollectionList->currentText()); - notification->setDataObject(options_page->UAVObject->currentText()); - notification->setObjectField(options_page->UAVObjectField->currentText()); - notification->setValue(options_page->Value->currentText()); - notification->setSpinBoxValue(options_page->ValueSpinBox->value()); - - if (options_page->Sound1->currentText().size() > 0) - notification->setSound1(options_page->Sound1->currentText()); - - notification->setSound2(options_page->Sound2->currentText()); - notification->setSound3(options_page->Sound3->currentText()); - -if ( ((!options_page->Sound2->currentText().size()) && (options_page->SayOrder->currentText()=="After second")) - || ((!options_page->Sound3->currentText().size()) && (options_page->SayOrder->currentText()=="After third")) ) { - return; - } else { - notification->setSayOrder(options_page->SayOrder->currentText()); - } - privListNotifications.append(notification); - emit entryAdded(privListNotifications.size() - 1); - _notifyRulesSelection->setCurrentIndex(_notifyRulesModel->index(privListNotifications.size()-1,0,QModelIndex()), - QItemSelectionModel::ClearAndSelect | QItemSelectionModel::Rows); -} - - -void NotifyPluginOptionsPage::on_buttonDeleteNotification_clicked() -{ - _notifyRulesModel->removeRow(_notifyRulesSelection->currentIndex().row()); - if (!_notifyRulesModel->rowCount() - && (_notifyRulesSelection->currentIndex().row() > 0 - && _notifyRulesSelection->currentIndex().row() < _notifyRulesModel->rowCount()) ) - { - options_page->buttonDelete->setEnabled(false); - options_page->buttonModify->setEnabled(false); - options_page->buttonPlayNotification->setEnabled(false); - } - -} - -void NotifyPluginOptionsPage::on_buttonModifyNotification_clicked() -{ - NotificationItem* notification = new NotificationItem; - getOptionsPageValues(notification); - notification->setRetryString(privListNotifications.at(_notifyRulesSelection->currentIndex().row())->retryString()); - notification->setLifetime(privListNotifications.at(_notifyRulesSelection->currentIndex().row())->lifetime()); - notification->setMute(privListNotifications.at(_notifyRulesSelection->currentIndex().row())->mute()); - - privListNotifications.replace(_notifyRulesSelection->currentIndex().row(),notification); - entryUpdated(_notifyRulesSelection->currentIndex().row()); - -} - From 27fca079d8c4a71f83ade37fb306bddc9bdeea45 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Sun, 29 Jul 2012 04:07:55 +1000 Subject: [PATCH 094/543] Change language used per David J's suggestion --- ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui index e9c3d7aaf..08118c4b5 100644 --- a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui +++ b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui @@ -341,7 +341,7 @@ - Problems + Messages From 14b7666c1b92003365025fe037d2d3d167477434 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 29 Jul 2012 00:44:08 +0100 Subject: [PATCH 095/543] GCS-disabled the reload board data button while it is doing its work. minimized uavo transactions when button is pressed. --- .../uavobjectwidgetutils/configtaskwidget.cpp | 14 ++++++++++++++ .../uavobjectwidgetutils/configtaskwidget.h | 10 ++++++++++ 2 files changed, 24 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 41ddf9f05..760ddae70 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -784,6 +784,9 @@ void ConfigTaskWidget::defaultButtonClicked() */ void ConfigTaskWidget::reloadButtonClicked() { + QPushButton * button=qobject_cast(sender()); + if(button) + button->setEnabled(false); int group=sender()->property("group").toInt(); QList * list=defaultReloadGroups.value(group,NULL); if(!list) @@ -793,10 +796,19 @@ void ConfigTaskWidget::reloadButtonClicked() QEventLoop * eventLoop=new QEventLoop(this); connect(timeOut, SIGNAL(timeout()),eventLoop,SLOT(quit())); connect(objper, SIGNAL(objectUpdated(UAVObject*)), eventLoop, SLOT(quit())); + + QList temp; foreach(objectToWidget * oTw,*list) { if (oTw->object != NULL) { + temphelper value; + value.objid=oTw->object->getObjID(); + value.objinstid=oTw->object->getInstID(); + if(temp.contains(value)) + continue; + else + temp.append(value); ObjectPersistence::DataFields data; data.Operation = ObjectPersistence::OPERATION_LOAD; data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT; @@ -824,6 +836,8 @@ void ConfigTaskWidget::reloadButtonClicked() delete timeOut; timeOut=NULL; } + if(button) + button->setEnabled(true); } /** diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index 3cac0abc0..825f9d007 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -70,6 +70,16 @@ public: QList shadowsList; }; + struct temphelper + { + quint32 objid; + quint32 objinstid; + bool operator==(const temphelper& lhs) + { + return (lhs.objid==this->objid && lhs.objinstid==this->objinstid); + } + }; + enum buttonTypeEnum {none,save_button,apply_button,reload_button,default_button,help_button}; struct uiRelationAutomation { From 6b84b58bfe154e706c4767f27d173f2c880e01ef Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 29 Jul 2012 00:53:05 +0100 Subject: [PATCH 096/543] GCS-Moved the wizard and calibration widgets to the stacked widget so that they disapear during the wizard --- .../src/plugins/config/configinputwidget.cpp | 15 +++++ .../src/plugins/config/configinputwidget.h | 5 +- .../openpilotgcs/src/plugins/config/input.ui | 55 +++++++------------ 3 files changed, 38 insertions(+), 37 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index f9c9e0a40..78f32055b 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -86,6 +86,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent) addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", m_config->deadband, 0, 0.01f); connect(m_config->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard())); + connect(m_config->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int))); connect(m_config->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool))); connect(m_config->wzNext,SIGNAL(clicked()),this,SLOT(wzNext())); @@ -303,6 +304,14 @@ void ConfigInputWidget::goToWizard() m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); } +void ConfigInputWidget::disableWizardButton(int value) +{ + if(value!=0) + m_config->configurationWizard->setVisible(false); + else + m_config->configurationWizard->setVisible(true); +} + void ConfigInputWidget::wzCancel() { dimOtherControls(false); @@ -404,6 +413,12 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) { switch(step) { case wizardWelcome: + foreach(QPointer wd,extraWidgets) + { + if(!wd.isNull()) + delete wd; + } + extraWidgets.clear(); m_config->graphicsView->setVisible(false); setTxMovement(nothing); manualSettingsData=manualSettingsObj->getData(); diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.h b/ground/openpilotgcs/src/plugins/config/configinputwidget.h index bc27467ca..4b28ca491 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.h @@ -45,6 +45,7 @@ #include #include "flightstatus.h" #include "accessorydesired.h" +#include class Ui_InputWidget; @@ -69,7 +70,7 @@ private: void setTxMovement(txMovements movement); Ui_InputWidget *m_config; wizardSteps wizardStep; - QList extraWidgets; + QList > extraWidgets; txMode transmitterMode; txType transmitterType; struct channelsStruct @@ -148,7 +149,7 @@ private slots: void wzBack(); void wzCancel(); void goToWizard(); - + void disableWizardButton(int); void openHelp(); void identifyControls(); void identifyLimits(); diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index a811c6754..5fffc2773 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -107,41 +107,12 @@ 0 0 - 663 - 745 + 671 + 755 - - - - 0 - 0 - - - - - - - - - - Start Configuration Wizard - - - - - - - Run Calibration - - - - - - - @@ -154,6 +125,20 @@ + + + + Start Configuration Wizard + + + + + + + Run Calibration + + + @@ -388,8 +373,8 @@ 0 0 - 648 - 776 + 508 + 770 @@ -923,8 +908,8 @@ margin:1px; 0 0 - 663 - 745 + 550 + 147 From ec3919d2b7d3b3c8d8d21d7807fa80b7734fa037 Mon Sep 17 00:00:00 2001 From: Dmytro Poplavskiy Date: Sun, 29 Jul 2012 12:17:10 +1000 Subject: [PATCH 097/543] Enabled osgEarth caching --- .../openpilotgcs/src/plugins/pfdqml/osgearth.cpp | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/pfdqml/osgearth.cpp b/ground/openpilotgcs/src/plugins/pfdqml/osgearth.cpp index b4e8ac53e..baf0fd2b5 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/osgearth.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/osgearth.cpp @@ -38,6 +38,8 @@ #include +#include "utils/pathutils.h" + OsgEarthItem::OsgEarthItem(QDeclarativeItem *parent): QDeclarativeItem(parent), m_fbo(0), @@ -290,6 +292,20 @@ void OsgEarthItem::initScene() m_model = osgDB::readNodeFile(sceneFile.toStdString()); + //setup caching + osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(m_model.get()); + if (mapNode) { + osgEarth::TMSCacheOptions cacheOptions; + //cacheOptions.cacheOnly() = true; + QString cacheDir = Utils::PathUtils().GetStoragePath()+QLatin1String("osgEarth_cache"); + cacheOptions.setPath(cacheDir.toStdString()); + osgEarth::Cache *cache= new osgEarth::TMSCache(cacheOptions); + + mapNode->getMap()->setCache(cache); + } else { + qWarning() << Q_FUNC_INFO << sceneFile << " doesn't look like an osgEarth file"; + } + m_gw = new osgViewer::GraphicsWindowEmbedded(0,0,w,h); m_viewer = new osgViewer::Viewer(); From 9d884ca12c9468cc1e156874955485387ff062a8 Mon Sep 17 00:00:00 2001 From: Dmytro Poplavskiy Date: Sun, 29 Jul 2012 16:05:59 +1000 Subject: [PATCH 098/543] PFD terrain view: switch between GPS and predefined positions. --- .../share/openpilotgcs/pfd/default/Pfd.qml | 42 +-- .../src/plugins/coreplugin/OpenPilotGCS.xml | 18 +- .../src/plugins/pfdqml/pfdqmlgadget.cpp | 13 + .../pfdqml/pfdqmlgadgetconfiguration.cpp | 22 +- .../pfdqml/pfdqmlgadgetconfiguration.h | 16 +- .../pfdqml/pfdqmlgadgetoptionspage.cpp | 16 +- .../plugins/pfdqml/pfdqmlgadgetoptionspage.ui | 355 +++++++++++++----- .../src/plugins/pfdqml/pfdqmlgadgetwidget.cpp | 41 +- .../src/plugins/pfdqml/pfdqmlgadgetwidget.h | 28 ++ 9 files changed, 423 insertions(+), 128 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml index 517aa5b6a..64df9502d 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml @@ -1,7 +1,6 @@ import Qt 4.7 import "." import org.OpenPilot 1.0 -//import "/home/dima/work/RC/OsgEarthQml-build-desktop-Qt_4_8_1_in_PATH__System__Debug" Rectangle { color: "#666666" @@ -23,6 +22,27 @@ Rectangle { anchors.centerIn: parent clip: true + OsgEarth { + id: earthView + + anchors.fill: parent + sceneFile: qmlWidget.earthFile + visible: qmlWidget.terrainEnabled + + fieldOfView: 90 + + yaw: AttitudeActual.Yaw + pitch: AttitudeActual.Pitch + roll: AttitudeActual.Roll + + latitude: qmlWidget.actualPositionUsed ? + GPSPosition.Latitude/10000000.0 : qmlWidget.latitude + longitude: qmlWidget.actualPositionUsed ? + GPSPosition.Longitude/10000000.0 : qmlWidget.longitude + altitude: qmlWidget.actualPositionUsed ? + GPSPosition.Altitude : qmlWidget.altitude + } + Image { id: world source: "image://svg/pfd.svg!world" @@ -44,26 +64,6 @@ Rectangle { ] } - OsgEarth { - id: earthView - - anchors.fill: parent - sceneFile: qmlWidget.earthFile - visible: qmlWidget.terrainEnabled - - fieldOfView: 90 - - yaw: AttitudeActual.Yaw - pitch: AttitudeActual.Pitch - roll: AttitudeActual.Roll - - - latitude: -27.935474 - longitude: 153.187147 - altitude: 3000 - //altitude: PositionActual.Down - } - Image { id: rollscale source: "image://svg/pfd.svg!rollscale" diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml index ac8ac26cc..b554fe74c 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml @@ -1698,9 +1698,14 @@ 0.0.0 + false + 2000 + false + %%DATAPATH%%pfd/pfd/default/readymap.earth + 46.671478 + 10.158932 + %%DATAPATH%%pfd/pfd/default/Pfd.qml false - %%DATAPATH%%pfd/default/Pfd.qml - %%DATAPATH%%pfd/default/srtm.earth @@ -1709,9 +1714,14 @@ 0.0.0 + false + 2000 + false + %%DATAPATH%%pfd/pfd/default/readymap.earth + 46.671478 + 10.158932 + %%DATAPATH%%pfd/pfd/default/Pfd.qml true - %%DATAPATH%%pfd/default/Pfd.qml - %%DATAPATH%%pfd/default/srtm.earth diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp index 48661a581..93427446c 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp @@ -41,4 +41,17 @@ void PfdQmlGadget::loadConfiguration(IUAVGadgetConfiguration* config) m_widget->setQmlFile(m->qmlFile()); m_widget->setEarthFile(m->earthFile()); m_widget->setTerrainEnabled(m->terrainEnabled()); + m_widget->setActualPositionUsed(m->actualPositionUsed()); + m_widget->setLatitude(m->latitude()); + m_widget->setLongitude(m->longitude()); + m_widget->setAltitude(m->altitude()); + + //setting OSGEARTH_CACHE_ONLY seems to work the most reliably + //between osgEarth versions I tried + if (m->cacheOnly()) { + qputenv("OSGEARTH_CACHE_ONLY", "true"); + } else { + //how portable it is? + unsetenv("OSGEARTH_CACHE_ONLY"); + } } diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.cpp index 56926917e..8a21da857 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.cpp @@ -25,7 +25,12 @@ PfdQmlGadgetConfiguration::PfdQmlGadgetConfiguration(QString classId, QSettings IUAVGadgetConfiguration(classId, parent), m_qmlFile("Unknown"), m_earthFile("Unknown"), - m_terrainEnabled(true) + m_terrainEnabled(true), + m_actualPositionUsed(false), + m_latitude(0), + m_longitude(0), + m_altitude(0), + m_cacheOnly(false) { //if a saved configuration exists load it if(qSettings != 0) { @@ -36,6 +41,11 @@ PfdQmlGadgetConfiguration::PfdQmlGadgetConfiguration(QString classId, QSettings m_earthFile=Utils::PathUtils().InsertDataPath(m_earthFile); m_terrainEnabled = qSettings->value("terrainEnabled").toBool(); + m_actualPositionUsed = qSettings->value("actualPositionUsed").toBool(); + m_latitude = qSettings->value("latitude").toDouble(); + m_longitude = qSettings->value("longitude").toDouble(); + m_altitude = qSettings->value("altitude").toDouble(); + m_cacheOnly = qSettings->value("cacheOnly").toBool(); } } @@ -49,6 +59,11 @@ IUAVGadgetConfiguration *PfdQmlGadgetConfiguration::clone() m->m_qmlFile = m_qmlFile; m->m_earthFile = m_earthFile; m->m_terrainEnabled = m_terrainEnabled; + m->m_actualPositionUsed = m_actualPositionUsed; + m->m_latitude = m_latitude; + m->m_longitude = m_longitude; + m->m_altitude = m_altitude; + m->m_cacheOnly = m_cacheOnly; return m; } @@ -64,4 +79,9 @@ void PfdQmlGadgetConfiguration::saveConfig(QSettings* qSettings) const { qSettings->setValue("earthFile", earthFile); qSettings->setValue("terrainEnabled", m_terrainEnabled); + qSettings->setValue("actualPositionUsed", m_actualPositionUsed); + qSettings->setValue("latitude", m_latitude); + qSettings->setValue("longitude", m_longitude); + qSettings->setValue("altitude", m_altitude); + qSettings->setValue("cacheOnly", m_cacheOnly); } diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.h b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.h index c9986173b..69205375c 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.h +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetconfiguration.h @@ -30,11 +30,20 @@ public: void setQmlFile(const QString &fileName) { m_qmlFile=fileName; } void setEarthFile(const QString &fileName) { m_earthFile=fileName; } void setTerrainEnabled(bool flag) { m_terrainEnabled = flag; } + void setActualPositionUsed(bool flag) { m_actualPositionUsed = flag; } + void setLatitude(double value) { m_latitude = value; } + void setLongitude(double value) { m_longitude = value; } + void setAltitude(double value) { m_altitude = value; } + void setCacheOnly(bool flag) { m_cacheOnly = flag; } - //get dial configuration functions QString qmlFile() const { return m_qmlFile; } QString earthFile() const { return m_earthFile; } bool terrainEnabled() const { return m_terrainEnabled; } + bool actualPositionUsed() const { return m_actualPositionUsed; } + double latitude() const { return m_latitude; } + double longitude() const { return m_longitude; } + double altitude() const { return m_altitude; } + bool cacheOnly() const { return m_cacheOnly; } void saveConfig(QSettings* settings) const; IUAVGadgetConfiguration *clone(); @@ -43,6 +52,11 @@ private: QString m_qmlFile; // The name of the dial's SVG source file QString m_earthFile; // The name of osgearth terrain file bool m_terrainEnabled; + bool m_actualPositionUsed; + double m_latitude; + double m_longitude; + double m_altitude; + bool m_cacheOnly; }; #endif // PfdQmlGADGETCONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp index 01ee89c96..a47b7acf5 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp @@ -35,10 +35,9 @@ PfdQmlGadgetOptionsPage::PfdQmlGadgetOptionsPage(PfdQmlGadgetConfiguration *conf //creates options page widget (uses the UI file) QWidget *PfdQmlGadgetOptionsPage::createPage(QWidget *parent) { - options_page = new Ui::PfdQmlGadgetOptionsPage(); //main widget - QWidget *optionsPageWidget = new QWidget; + QWidget *optionsPageWidget = new QWidget(parent); //main layout options_page->setupUi(optionsPageWidget); @@ -56,6 +55,13 @@ QWidget *PfdQmlGadgetOptionsPage::createPage(QWidget *parent) options_page->showTerrain->setChecked(m_config->terrainEnabled()); + options_page->useActualLocation->setChecked(m_config->actualPositionUsed()); + options_page->usePredefinedLocation->setChecked(!m_config->actualPositionUsed()); + options_page->latitude->setText(QString::number(m_config->latitude())); + options_page->longitude->setText(QString::number(m_config->longitude())); + options_page->altitude->setText(QString::number(m_config->altitude())); + options_page->useOnlyCache->setChecked(m_config->cacheOnly()); + return optionsPageWidget; } @@ -70,6 +76,12 @@ void PfdQmlGadgetOptionsPage::apply() m_config->setQmlFile(options_page->qmlSourceFile->path()); m_config->setEarthFile(options_page->earthFile->path()); m_config->setTerrainEnabled(options_page->showTerrain->isChecked()); + + m_config->setActualPositionUsed(options_page->useActualLocation->isChecked()); + m_config->setLatitude(options_page->latitude->text().toDouble()); + m_config->setLongitude(options_page->longitude->text().toDouble()); + m_config->setAltitude(options_page->altitude->text().toDouble()); + m_config->setCacheOnly(options_page->useOnlyCache->isChecked()); } void PfdQmlGadgetOptionsPage::finish() diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui index dd8d03e4f..3f244043b 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui @@ -6,8 +6,8 @@ 0 0 - 441 - 339 + 457 + 436 @@ -19,107 +19,217 @@ Form - + + + 0 + + + 0 + - - - 10 + + + QFrame::NoFrame - - QLayout::SetMaximumSize + + 0 - - 10 - - - - - QML file: - - - - - - - - 0 - 0 - - - - - - - - - - Qt::Horizontal + + true + + + + 0 + 0 + 457 + 436 + + + + + + + 10 + + + QLayout::SetMaximumSize + + + 10 + + + + + QML file: + + + + + + + + 0 + 0 + + + + + + + + + + Show Terrain: + + + true + + + + + + 10 + + + QLayout::SetMaximumSize + + + 10 + + + + + OsgEarth file: + + + + + + + + 0 + 0 + + + + + + + + + + Use actual location + + + + + + + Use pre-defined location: + + + true + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 16 + 16 + + + + + + + + + + Latitude: + + + + + + + + + + Longitude: + + + + + + + + + + Altitude: + + + + + + + + + + + + Use only cache data + + + + + + + Qt::Horizontal + + + + 74 + 24 + + + + + + + + Pre seed terrain cache + + + + + + + + + + Qt::Vertical + + + + 20 + 121 + + + + + + - - - - - - true - - - Show terrain - - - true - - - - - - - - - 10 - - - QLayout::SetMaximumSize - - - 10 - - - - - OsgEarth file: - - - - - - - - 0 - 0 - - - - - - - - - - Qt::Vertical - - - QSizePolicy::MinimumExpanding - - - - 20 - 40 - - - - @@ -131,5 +241,54 @@ - + + + usePredefinedLocation + toggled(bool) + latitude + setEnabled(bool) + + + 150 + 138 + + + 142 + 172 + + + + + usePredefinedLocation + toggled(bool) + longitude + setEnabled(bool) + + + 164 + 141 + + + 164 + 202 + + + + + usePredefinedLocation + toggled(bool) + altitude + setEnabled(bool) + + + 190 + 141 + + + 190 + 237 + + + + diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp index 40c748239..311f106a5 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp @@ -33,7 +33,11 @@ PfdQmlGadgetWidget::PfdQmlGadgetWidget(QWidget *parent) : QDeclarativeView(parent), - m_terrainEnabled(false) + m_terrainEnabled(false), + m_actualPositionUsed(false), + m_latitude(46.671478), + m_longitude(10.158932), + m_altitude(2000) { setMinimumSize(64,64); setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); @@ -105,3 +109,38 @@ void PfdQmlGadgetWidget::setTerrainEnabled(bool arg) emit terrainEnabledChanged(arg); } } + +//Switch between PositionActual UAVObject position +//and pre-defined latitude/longitude/altitude properties +void PfdQmlGadgetWidget::setActualPositionUsed(bool arg) +{ + if (m_actualPositionUsed != arg) { + m_actualPositionUsed = arg; + emit actualPositionUsedChanged(arg); + } +} + +void PfdQmlGadgetWidget::setLatitude(double arg) +{ + //not sure qFuzzyCompare is accurate enough for geo coordinates + if (m_latitude != arg) { + m_latitude = arg; + emit latitudeChanged(arg); + } +} + +void PfdQmlGadgetWidget::setLongitude(double arg) +{ + if (m_longitude != arg) { + m_longitude = arg; + emit longitudeChanged(arg); + } +} + +void PfdQmlGadgetWidget::setAltitude(double arg) +{ + if (!qFuzzyCompare(m_altitude,arg)) { + m_altitude = arg; + emit altitudeChanged(arg); + } +} diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.h b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.h index 6e0f8b35f..ba89f282c 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.h @@ -26,6 +26,13 @@ class PfdQmlGadgetWidget : public QDeclarativeView Q_PROPERTY(QString earthFile READ earthFile WRITE setEarthFile NOTIFY earthFileChanged) Q_PROPERTY(bool terrainEnabled READ terrainEnabled WRITE setTerrainEnabled NOTIFY terrainEnabledChanged) + Q_PROPERTY(bool actualPositionUsed READ actualPositionUsed WRITE setActualPositionUsed NOTIFY actualPositionUsedChanged) + + //pre-defined fallback position + Q_PROPERTY(double latitude READ latitude WRITE setLatitude NOTIFY latitudeChanged) + Q_PROPERTY(double longitude READ longitude WRITE setLongitude NOTIFY longitudeChanged) + Q_PROPERTY(double altitude READ altitude WRITE setAltitude NOTIFY altitudeChanged) + public: PfdQmlGadgetWidget(QWidget *parent = 0); ~PfdQmlGadgetWidget(); @@ -34,18 +41,39 @@ public: QString earthFile() const { return m_earthFile; } bool terrainEnabled() const { return m_terrainEnabled; } + bool actualPositionUsed() const { return m_actualPositionUsed; } + double latitude() const { return m_latitude; } + double longitude() const { return m_longitude; } + double altitude() const { return m_altitude; } + public slots: void setEarthFile(QString arg); void setTerrainEnabled(bool arg); + void setLatitude(double arg); + void setLongitude(double arg); + void setAltitude(double arg); + + void setActualPositionUsed(bool arg); + signals: void earthFileChanged(QString arg); void terrainEnabledChanged(bool arg); + void actualPositionUsedChanged(bool arg); + void latitudeChanged(double arg); + void longitudeChanged(double arg); + void altitudeChanged(double arg); + private: QString m_qmlFileName; QString m_earthFile; bool m_terrainEnabled; + + bool m_actualPositionUsed; + double m_latitude; + double m_longitude; + double m_altitude; }; #endif /* PFDQMLGADGETWIDGET_H_ */ From 19b101bc4b0219dbe4278c3df7d224da4d79dfbd Mon Sep 17 00:00:00 2001 From: David Ankers Date: Sun, 29 Jul 2012 21:28:32 +1000 Subject: [PATCH 099/543] Make a start on the new layout --- .../src/plugins/coreplugin/OpenPilotGCS.xml | 441 ++++++------------ .../src/plugins/coreplugin/core.qrc | 1 + .../src/plugins/coreplugin/images/cpu.png | Bin 0 -> 1466 bytes 3 files changed, 140 insertions(+), 302 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/coreplugin/images/cpu.png diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml index 490f9f85e..87547960e 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml @@ -21,41 +21,9 @@ 89 88 87 + 86 100 - - - - false - 1.0.0 - - - - - - - 0 - false - - 0 - 0 - 0 - - - - - - 0 - - 1 - - false - - 0 - - - - @@ -1733,6 +1701,7 @@ false false + 1000 60 @@ -1778,6 +1747,7 @@ false false + 1000 20 @@ -1833,6 +1803,7 @@ false false + 1000 60 @@ -1878,6 +1849,7 @@ false false + 1000 60 @@ -1903,6 +1875,7 @@ false false + 1000 40 @@ -1998,6 +1971,7 @@ false false + 1000 60 @@ -2043,6 +2017,7 @@ false false + 1000 60 @@ -2088,6 +2063,7 @@ false false + 1000 60 @@ -2133,6 +2109,7 @@ false false + 1000 240 @@ -2268,6 +2245,7 @@ false false + 1000 20 @@ -2313,6 +2291,7 @@ false false + 1000 240 @@ -2327,6 +2306,9 @@ 0 + + + 0 1 0 @@ -2395,45 +2377,45 @@ - - LineardialGadget - - Flight Time - - uavGadget - - - LineardialGadget - - GPS Sats - - uavGadget - - 2 - @Variant(AAAACQAAAAA=) - splitter + LineardialGadget + + Flight Time + + uavGadget LineardialGadget - Flight mode + Arm Status uavGadget - LineardialGadget - - Arm Status - - uavGadget + + LineardialGadget + + Flight mode + + uavGadget + + + LineardialGadget + + GPS Sats + + uavGadget + + 1 + @Variant(AAAACQAAAAIAAAACAAAAoAAAAAIAAACk) + splitter - 2 - @Variant(AAAACQAAAAA=) + 1 + @Variant(AAAACQAAAAIAAAACAAAAmQAAAAIAAAFC) splitter - 2 - @Variant(AAAACQAAAAIAAAACAAAA1wAAAAIAAADt) + 1 + @Variant(AAAACQAAAAIAAAACAAAAmQAAAAIAAAHc) splitter @@ -2443,8 +2425,8 @@ uavGadget - 1 - @Variant(AAAACQAAAAIAAAACAAAAkAAAAAIAAAJg) + 2 + @Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAG4) splitter @@ -2456,185 +2438,29 @@ uavGadget - - - SystemHealthGadget - - default - - uavGadget - - - LineardialGadget - - Mainboard CPU - - uavGadget - - 1 - @Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAACB) - splitter - - - - LineardialGadget - - Telemetry RX Rate Horizontal - - uavGadget - - - LineardialGadget - - Telemetry TX Rate Horizontal - - uavGadget - - 1 - @Variant(AAAACQAAAAA=) - splitter - - 2 - @Variant(AAAACQAAAAIAAAACAAABJQAAAAIAAABA) - splitter + SystemHealthGadget + + default + + uavGadget 1 - @Variant(AAAACQAAAAIAAAACAAABMAAAAAIAAAGx) + @Variant(AAAACQAAAAIAAAACAAABIAAAAAIAAAFV) splitter 2 - @Variant(AAAACQAAAAIAAAACAAABxQAAAAIAAAFH) + @Variant(AAAACQAAAAIAAAACAAAB7wAAAAIAAAEf) splitter - - OPMapGadget - - Google Sat - - uavGadget - - - - - - - DialGadget - - Deluxe Groundspeed kph - - uavGadget - - - DialGadget - - Deluxe Barometer - - uavGadget - - 2 - @Variant(AAAACQAAAAA=) - splitter - - - - DialGadget - - Deluxe Attitude - - uavGadget - - - DialGadget - - Deluxe Compass - - uavGadget - - 2 - @Variant(AAAACQAAAAA=) - splitter - - 1 - @Variant(AAAACQAAAAIAAAACAAAAgwAAAAIAAACK) - splitter - - - - DialGadget - - Deluxe Baro Altimeter - - uavGadget - - - DialGadget - - Deluxe Climbrate - - uavGadget - - 2 - @Variant(AAAACQAAAAA=) - splitter - - 1 - @Variant(AAAACQAAAAIAAAACAAABFQAAAAIAAACH) - splitter - - - - LineardialGadget - - Throttle - - uavGadget - - - - LineardialGadget - - Roll Desired - - uavGadget - - - - LineardialGadget - - Pitch Desired - - uavGadget - - - LineardialGadget - - Yaw Desired - - uavGadget - - 1 - @Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAE3) - splitter - - 1 - @Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAF4) - splitter - - 1 - @Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAG5) - splitter - - 1 - @Variant(AAAACQAAAAIAAAACAAABuQAAAAIAAAED) - splitter - - 2 - @Variant(AAAACQAAAAIAAAACAAAB7AAAAAIAAAEg) - splitter + OPMapGadget + + Google Sat + + uavGadget 1 - @Variant(AAAACQAAAAIAAAACAAAC4gAAAAIAAAK9) + @Variant(AAAACQAAAAIAAAACAAACdgAAAAIAAAMp) splitter UAVGadgetManagerV1 @@ -2651,6 +2477,44 @@ UAVGadgetManagerV1 + false + + + + UAVObjectBrowser + + default + + uavGadget + + + DebugGadget + uavGadget + + 1 + @Variant(AAAACQAAAAA=) + splitter + + + + EmptyGadget + uavGadget + + + EmptyGadget + uavGadget + + 1 + @Variant(AAAACQAAAAA=) + splitter + + 2 + @Variant(AAAACQAAAAIAAAACAAACJgAAAAIAAADo) + splitter + + UAVGadgetManagerV1 + + false @@ -2705,8 +2569,8 @@ splitter UAVGadgetManagerV1 - - + + false @@ -2718,66 +2582,39 @@ uavGadget - - GCSControlGadget - - MS Sidewinder - - uavGadget - - - - - LineardialGadget - - Pitch Desired - - uavGadget - - - LineardialGadget - - PitchActual - - uavGadget - - 1 - @Variant(AAAACQAAAAA=) - splitter - - - LineardialGadget - - Pitch - - uavGadget - - 1 - @Variant(AAAACQAAAAIAAAACAAABFAAAAAIAAABA) - splitter - - 1 - @Variant(AAAACQAAAAIAAAACAAAB6AAAAAIAAADC) - splitter + HITLv2 + + default + + uavGadget - 2 - @Variant(AAAACQAAAAIAAAACAAABaQAAAAIAAAEO) + 1 + @Variant(AAAACQAAAAA=) splitter - UAVObjectBrowser - - default - - uavGadget + + EmptyGadget + uavGadget + + + GCSControlGadget + + MS Sidewinder + + uavGadget + + 1 + @Variant(AAAACQAAAAIAAAACAAAB6AAAAAIAAADC) + splitter - 1 + 2 @Variant(AAAACQAAAAIAAAACAAADDAAAAAIAAAJJ) splitter UAVGadgetManagerV1 - - + + false @@ -2790,16 +2627,16 @@ - SystemHealthGadget + LineardialGadget - default + Flight Time uavGadget - PFDGadget + SystemHealthGadget - raw + default uavGadget @@ -2808,44 +2645,44 @@ splitter - ScopeGadget + PFDGadget - Uptimes + raw uavGadget 2 - @Variant(AAAACQAAAAIAAAACAAABEgAAAAIAAAH6) + @Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAAHf) splitter 1 - @Variant(AAAACQAAAAA=) + @Variant(AAAACQAAAAIAAAACAAADVQAAAAIAAAJK) splitter UAVGadgetManagerV1 - + false :\core\images\ah.png :/core/images/openpilot_logo_64.png :/core/images/config.png - :/core/images/scopes.png - :/core/images/joystick.png - :/core/images/cog.png - :/core/images/openpilot_logo_64.png + :/core/images/cpu.png + :/core/images/scopes.png + :/core/images/joystick.png + :/core/images/cog.png :/core/images/openpilot_logo_64.png :/core/images/openpilot_logo_64.png :/core/images/openpilot_logo_64.png - 5 + 6 1 Flight data Workspace10 Configuration - Scopes - HITL - Firmware - Workspace6 + System + Scopes + HITL + Firmware Workspace7 Workspace8 Workspace9 diff --git a/ground/openpilotgcs/src/plugins/coreplugin/core.qrc b/ground/openpilotgcs/src/plugins/coreplugin/core.qrc index c1b0f8e36..d65e51376 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/core.qrc +++ b/ground/openpilotgcs/src/plugins/coreplugin/core.qrc @@ -61,5 +61,6 @@ images/cog.png OpenPilotGCS.xml images/helpicon.svg + images/cpu.png diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/cpu.png b/ground/openpilotgcs/src/plugins/coreplugin/images/cpu.png new file mode 100644 index 0000000000000000000000000000000000000000..d5b42c728447b2cc744ed7c429aa3ef68e50af53 GIT binary patch literal 1466 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`k|nMYCBgY=CFO}lsSJ)O`AMk? zp1FzXsX?iUDV2pMQ*9U+n3Xa^B1$5BeXNr6bM+EIYV;~{3xK*A7;Nk-3KEmEQ%e+* zQqwc@Y?a>c-mj#PnPRIHZt82`Ti~3Uk?B!Ylp0*+7m{3+ootz+WN)WnQ(*-(AUCxn zQK2F?C$HG5!d3}vt`(3C64qBz04piUwpD^SD#ABF!8yMuRl!uxKsVXI%uvD1M9IxIyg#@@$ndN=gc>^!3Zj z%k|2Q_413-^$jg8E%gnI^o@*kfhu&1EAvVcD|GXUm0>2hq!uR^WfqiV=I1GZOiWD5 zFD$Tv3bSNU;+l1ennz|zM-B0$V)JVzP|XC=H|jx7ncO3BHWAB;NpiyW)Z+ZoqGVvir744~DzI`cN=+=uFAB-e&w+(vKt_H^esM;Afr4|esh*)icxGNo zet9uiy|1s8XI^nhVqS8pr;Du;&;-5A%oHm(M?+^z3kxF`OEWh^Lsvr!M+;*|S7T!n zAk)pn$r+~CB|o_|H#M&WrZ)wl*BGZ>P*TV(0NU)5T9jFqn&MWJpQ`}&vQ;K-w;13w z52`l>w_6Nx>eUB2MjsThND&Pa0;V1i6P|2=9C*S{%>$7Xs4l*cz<_=dd|ByMHtP!^rnr^sH3N0>8tKT20LI%z{de z8m>yF-Em#hqJGcY`XJ_=>-*NzwgndLd%thrcRVUu$mv17+)sb$`1trF6RCwUddb<@ z+;#iq^RMKrq7Jhtx*p@eiRH35BE@;{G!C_#n-AIfBvwD@7TXzd}Rn%^FfA-8B-cJ-{d*{ zR48TQrWMy;$DDXu_W9S>ucr6z-CIyLkGRc(hAW%$^g7775p zld}2d86UUBg6r3>f75+n`}XZCu4bJ`G2+QHk-8(ArON7&YdX_s!b&Svmp41Pc``{6&KGwWx&sG5BI^y$#v zwINy({m18Y&gy;jGyGZa;x$|R1tMm0r!8Y*QA*o=S1)&$advs5p5WF=ITu!6&AP64 iA)fos>(9;&j0`SW-gd8MTzdg3O+8)xT-G@yGywoP@+5r# literal 0 HcmV?d00001 From c7b8fe9efd6ca827a907d4fa2ffcda8161b97f15 Mon Sep 17 00:00:00 2001 From: Dmytro Poplavskiy Date: Sun, 29 Jul 2012 22:15:24 +1000 Subject: [PATCH 100/543] Moved terrain rendering to background thread osgEarth may block the main thread during network io, the rendering is moved to OsgEarthItemRenderer class, running in the bg thread. May require Qt 4.8.0+ to work correctly. --- ground/openpilotgcs/src/app/main.cpp | 1 + .../src/plugins/pfdqml/osgearth.cpp | 281 +++++++++++------- .../src/plugins/pfdqml/osgearth.h | 51 +++- 3 files changed, 212 insertions(+), 121 deletions(-) diff --git a/ground/openpilotgcs/src/app/main.cpp b/ground/openpilotgcs/src/app/main.cpp index ec2191956..a8f83b68f 100644 --- a/ground/openpilotgcs/src/app/main.cpp +++ b/ground/openpilotgcs/src/app/main.cpp @@ -239,6 +239,7 @@ int main(int argc, char **argv) setrlimit(RLIMIT_NOFILE, &rl); #endif + QApplication::setAttribute(Qt::AA_X11InitThreads, true); QApplication::setGraphicsSystem("raster"); SharedTools::QtSingleApplication app((QLatin1String(appNameC)), argc, argv); diff --git a/ground/openpilotgcs/src/plugins/pfdqml/osgearth.cpp b/ground/openpilotgcs/src/plugins/pfdqml/osgearth.cpp index baf0fd2b5..ce8880ad9 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/osgearth.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/osgearth.cpp @@ -17,6 +17,7 @@ #include "osgearth.h" #include +#include #include #include #include @@ -42,7 +43,8 @@ OsgEarthItem::OsgEarthItem(QDeclarativeItem *parent): QDeclarativeItem(parent), - m_fbo(0), + m_renderer(0), + m_rendererThread(0), m_currentSize(640, 480), m_roll(0.0), m_pitch(0.0), @@ -51,8 +53,7 @@ OsgEarthItem::OsgEarthItem(QDeclarativeItem *parent): m_longitude(153.0), m_altitude(400.0), m_fieldOfView(90.0), - m_sceneFile(QLatin1String("/usr/share/osgearth/maps/srtm.earth")), - m_cameraDirty(false) + m_sceneFile(QLatin1String("/usr/share/osgearth/maps/srtm.earth")) { setSize(m_currentSize); setFlag(ItemHasNoContents, false); @@ -60,6 +61,31 @@ OsgEarthItem::OsgEarthItem(QDeclarativeItem *parent): OsgEarthItem::~OsgEarthItem() { + if (m_renderer) { + m_rendererThread->exit(); + //wait up to 10 seconds for renderer thread to exit + m_rendererThread->wait(10*1000); + + delete m_renderer; + delete m_rendererThread; + } +} + +QString OsgEarthItem::resolvedSceneFile() const +{ + QString sceneFile = m_sceneFile; + + //try to resolve the relative scene file name: + if (!QFileInfo(sceneFile).exists()) { + QDeclarativeView *view = qobject_cast(scene()->views().first()); + + if (view) { + QUrl baseUrl = view->engine()->baseUrl(); + sceneFile = baseUrl.resolved(sceneFile).toLocalFile(); + } + } + + return sceneFile; } void OsgEarthItem::geometryChanged(const QRectF &newGeometry, const QRectF &oldGeometry) @@ -95,107 +121,43 @@ void OsgEarthItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *styl Q_UNUSED(style); QGLWidget *glWidget = qobject_cast(widget); - if (!m_glWidget) { - //make a shared gl widget to avoid - //osg rendering to mess with qpainter state - m_glWidget = new QGLWidget(widget, glWidget); - m_glWidget.data()->setAttribute(Qt::WA_PaintOutsidePaintEvent); - } + if (!m_renderer) { + m_renderer = new OsgEarthItemRenderer(this, glWidget); + connect(m_renderer, SIGNAL(frameReady()), + this, SLOT(updateView()), Qt::QueuedConnection); - if (!m_viewer.get()) - QMetaObject::invokeMethod(this, "initScene", Qt::QueuedConnection); + m_rendererThread = new QThread(this); + m_renderer->moveToThread(m_rendererThread); + m_rendererThread->start(); - if (glWidget && m_fbo) - glWidget->drawTexture(boundingRect(), m_fbo->texture()); -} - -void OsgEarthItem::markCameraDirty() -{ - m_cameraDirty = true; - QMetaObject::invokeMethod(this, "updateFBO", Qt::QueuedConnection); -} - -void OsgEarthItem::updateFBO() -{ - if (!m_cameraDirty || !m_viewer.get() || m_glWidget.isNull()) + QMetaObject::invokeMethod(m_renderer, "initScene", Qt::QueuedConnection); return; - - m_cameraDirty = false; - m_glWidget.data()->makeCurrent(); - - if (m_fbo && m_fbo->size() != m_currentSize) { - delete m_fbo; - m_fbo = 0; } - if (!m_fbo) { - m_fbo = new QGLFramebufferObject(m_currentSize, QGLFramebufferObject::CombinedDepthStencil); - QPainter p(m_fbo); - p.fillRect(0,0,m_currentSize.width(), m_currentSize.height(), Qt::gray); - } + QGLFramebufferObject *fbo = m_renderer->lastFrame(); - //To find a camera view matrix, find placer matrixes for two points - //onr at requested coords and another latitude shifted by 0.01 deg - osgEarth::Util::ObjectPlacer placer(m_viewer->getSceneData()); - - osg::Matrixd positionMatrix; - placer.createPlacerMatrix(m_latitude, m_longitude, m_altitude, positionMatrix); - osg::Matrixd positionMatrix2; - placer.createPlacerMatrix(m_latitude+0.01, m_longitude, m_altitude, positionMatrix2); - - osg::Vec3d eye(0.0f, 0.0f, 0.0f); - osg::Vec3d viewVector(0.0f, 0.0f, 0.0f); - osg::Vec3d upVector(0.0f, 0.0f, 1.0f); - - eye = positionMatrix.preMult(eye); - upVector = positionMatrix.preMult(upVector); - upVector.normalize(); - viewVector = positionMatrix2.preMult(viewVector) - eye; - viewVector.normalize(); - viewVector *= 10.0; - - //TODO: clarify the correct rotation order, - //currently assuming yaw, pitch, roll - osg::Quat q; - q.makeRotate(-m_yaw*M_PI/180.0, upVector); - upVector = q * upVector; - viewVector = q * viewVector; - - osg::Vec3d side = viewVector ^ upVector; - q.makeRotate(m_pitch*M_PI/180.0, side); - upVector = q * upVector; - viewVector = q * viewVector; - - q.makeRotate(m_roll*M_PI/180.0, viewVector); - upVector = q * upVector; - viewVector = q * viewVector; - - osg::Vec3d center = eye + viewVector; - -// qDebug() << "e " << eye.x() << eye.y() << eye.z(); -// qDebug() << "c " << center.x() << center.y() << center.z(); -// qDebug() << "up" << upVector.x() << upVector.y() << upVector.z(); - - m_viewer->getCamera()->setViewMatrixAsLookAt(osg::Vec3d(eye.x(), eye.y(), eye.z()), - osg::Vec3d(center.x(), center.y(), center.z()), - osg::Vec3d(upVector.x(), upVector.y(), upVector.z())); - - { - QPainter fboPainter(m_fbo); - fboPainter.beginNativePainting(); - m_viewer->frame(); - fboPainter.endNativePainting(); - } - m_glWidget.data()->doneCurrent(); + if (glWidget && fbo) + glWidget->drawTexture(boundingRect(), fbo->texture()); +} +void OsgEarthItem::updateView() +{ update(); } +void OsgEarthItem::updateFrame() +{ + if (m_renderer) { + m_renderer->markDirty(); + QMetaObject::invokeMethod(m_renderer, "updateFrame", Qt::QueuedConnection); + } +} + void OsgEarthItem::setRoll(qreal arg) { if (!qFuzzyCompare(m_roll, arg)) { m_roll = arg; - markCameraDirty(); + updateFrame(); emit rollChanged(arg); } } @@ -204,7 +166,7 @@ void OsgEarthItem::setPitch(qreal arg) { if (!qFuzzyCompare(m_pitch, arg)) { m_pitch = arg; - markCameraDirty(); + updateFrame(); emit pitchChanged(arg); } } @@ -213,7 +175,7 @@ void OsgEarthItem::setYaw(qreal arg) { if (!qFuzzyCompare(m_yaw, arg)) { m_yaw = arg; - markCameraDirty(); + updateFrame(); emit yawChanged(arg); } } @@ -250,14 +212,15 @@ void OsgEarthItem::setFieldOfView(qreal arg) m_fieldOfView = arg; emit fieldOfViewChanged(arg); - if (m_viewer.get()) { + //it should be a queued call to OsgEarthItemRenderer instead + /*if (m_viewer.get()) { m_viewer->getCamera()->setProjectionMatrixAsPerspective( m_fieldOfView, qreal(m_currentSize.width())/m_currentSize.height(), 1.0f, 10000.0f); - } + }*/ - markCameraDirty(); + updateFrame(); } } @@ -269,27 +232,51 @@ void OsgEarthItem::setSceneFile(QString arg) } } - -void OsgEarthItem::initScene() +OsgEarthItemRenderer::OsgEarthItemRenderer(OsgEarthItem *item, QGLWidget *glWidget) : + QObject(0), + m_item(item), + m_lastFboNumber(0), + m_currentSize(640, 480), + m_cameraDirty(false) { - if (m_viewer.get()) - return; + //make a shared gl widget to avoid + //osg rendering to mess with qpainter state + //this runs in the main thread + m_glWidget = new QGLWidget(0, glWidget); + m_glWidget.data()->setAttribute(Qt::WA_PaintOutsidePaintEvent); + + for (int i=0; imakeCurrent(); + for (int i=0; idoneCurrent(); + + delete m_glWidget.data(); +} + +QGLFramebufferObject *OsgEarthItemRenderer::lastFrame() +{ + return m_fbo[m_lastFboNumber]; +} + +void OsgEarthItemRenderer::initScene() +{ + Q_ASSERT(!m_viewer.get()); int w = m_currentSize.width(); int h = m_currentSize.height(); - QString sceneFile = m_sceneFile; - - //try to resolve the relative scene file name: - if (!QFileInfo(sceneFile).exists()) { - QDeclarativeView *view = qobject_cast(scene()->views().first()); - - if (view) { - QUrl baseUrl = view->engine()->baseUrl(); - sceneFile = baseUrl.resolved(sceneFile).toLocalFile(); - } - } - + QString sceneFile = m_item->resolvedSceneFile(); m_model = osgDB::readNodeFile(sceneFile.toStdString()); //setup caching @@ -320,8 +307,76 @@ void OsgEarthItem::initScene() // configure the near/far so we don't clip things that are up close camera->setNearFarRatio(0.00002); - camera->setProjectionMatrixAsPerspective(m_fieldOfView, qreal(w)/h, 1.0f, 10000.0f); + camera->setProjectionMatrixAsPerspective(m_item->fieldOfView(), qreal(w)/h, 1.0f, 10000.0f); - markCameraDirty(); + updateFrame(); } +void OsgEarthItemRenderer::updateFrame() +{ + if (!m_cameraDirty || !m_viewer.get() || m_glWidget.isNull()) + return; + + m_glWidget.data()->makeCurrent(); + + //To find a camera view matrix, find placer matrixes for two points + //onr at requested coords and another latitude shifted by 0.01 deg + osgEarth::Util::ObjectPlacer placer(m_viewer->getSceneData()); + + m_cameraDirty = false; + + osg::Matrixd positionMatrix; + placer.createPlacerMatrix(m_item->latitude(), m_item->longitude(), m_item->altitude(), positionMatrix); + osg::Matrixd positionMatrix2; + placer.createPlacerMatrix(m_item->latitude()+0.01, m_item->longitude(), m_item->altitude(), positionMatrix2); + + osg::Vec3d eye(0.0f, 0.0f, 0.0f); + osg::Vec3d viewVector(0.0f, 0.0f, 0.0f); + osg::Vec3d upVector(0.0f, 0.0f, 1.0f); + + eye = positionMatrix.preMult(eye); + upVector = positionMatrix.preMult(upVector); + upVector.normalize(); + viewVector = positionMatrix2.preMult(viewVector) - eye; + viewVector.normalize(); + viewVector *= 10.0; + + //TODO: clarify the correct rotation order, + //currently assuming yaw, pitch, roll + osg::Quat q; + q.makeRotate(-m_item->yaw()*M_PI/180.0, upVector); + upVector = q * upVector; + viewVector = q * viewVector; + + osg::Vec3d side = viewVector ^ upVector; + q.makeRotate(m_item->pitch()*M_PI/180.0, side); + upVector = q * upVector; + viewVector = q * viewVector; + + q.makeRotate(m_item->roll()*M_PI/180.0, viewVector); + upVector = q * upVector; + viewVector = q * viewVector; + + osg::Vec3d center = eye + viewVector; + +// qDebug() << "e " << eye.x() << eye.y() << eye.z(); +// qDebug() << "c " << center.x() << center.y() << center.z(); +// qDebug() << "up" << upVector.x() << upVector.y() << upVector.z(); + + m_viewer->getCamera()->setViewMatrixAsLookAt(osg::Vec3d(eye.x(), eye.y(), eye.z()), + osg::Vec3d(center.x(), center.y(), center.z()), + osg::Vec3d(upVector.x(), upVector.y(), upVector.z())); + + { + QGLFramebufferObject *fbo = m_fbo[(m_lastFboNumber + 1) % FboCount]; + QPainter fboPainter(fbo); + fboPainter.beginNativePainting(); + m_viewer->frame(); + fboPainter.endNativePainting(); + } + m_glWidget.data()->doneCurrent(); + + m_lastFboNumber = (m_lastFboNumber + 1) % FboCount; + + emit frameReady(); +} diff --git a/ground/openpilotgcs/src/plugins/pfdqml/osgearth.h b/ground/openpilotgcs/src/plugins/pfdqml/osgearth.h index 6a1095a07..8d0d3f6fe 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/osgearth.h +++ b/ground/openpilotgcs/src/plugins/pfdqml/osgearth.h @@ -24,6 +24,7 @@ class QGLFramebufferObject; class QGLWidget; +class OsgEarthItemRenderer; class OsgEarthItem : public QDeclarativeItem { @@ -46,6 +47,7 @@ public: ~OsgEarthItem(); QString sceneFile() const { return m_sceneFile; } + QString resolvedSceneFile() const; qreal fieldOfView() const { return m_fieldOfView; } qreal roll() const { return m_roll; } @@ -61,6 +63,7 @@ protected: void paint(QPainter *painter, const QStyleOptionGraphicsItem *style, QWidget *widget); public slots: + void updateView(); void setSceneFile(QString arg); void setFieldOfView(qreal arg); @@ -85,16 +88,12 @@ signals: void fieldOfViewChanged(qreal arg); private slots: - void markCameraDirty(); - void updateFBO(); - void initScene(); + void updateFrame(); private: - osg::ref_ptr m_viewer; - osg::ref_ptr m_gw; - osg::ref_ptr m_model; - QWeakPointer m_glWidget; - QGLFramebufferObject *m_fbo; + OsgEarthItemRenderer *m_renderer; + QThread *m_rendererThread; + QSize m_currentSize; qreal m_roll; @@ -108,6 +107,42 @@ private: qreal m_fieldOfView; QString m_sceneFile; +}; + +class OsgEarthItemRenderer : public QObject +{ + Q_OBJECT +public: + OsgEarthItemRenderer(OsgEarthItem *item, QGLWidget *glWidget); + ~OsgEarthItemRenderer(); + + QGLFramebufferObject *lastFrame(); + void markDirty() { m_cameraDirty = true; } + +public slots: + void initScene(); + void updateFrame(); + +signals: + void frameReady(); + +private slots: + void updateFBO(); + +private: + enum { FboCount = 3 }; + OsgEarthItem *m_item; + + osg::ref_ptr m_viewer; + osg::ref_ptr m_gw; + osg::ref_ptr m_model; + QWeakPointer m_glWidget; + + QGLFramebufferObject* m_fbo[FboCount]; + int m_lastFboNumber; + + QSize m_currentSize; + bool m_cameraDirty; }; From cc512715b98ce3edc64797845960a18dc36bca72 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Sun, 29 Jul 2012 22:25:06 +1000 Subject: [PATCH 101/543] Update icon to a better one --- .../src/plugins/coreplugin/images/cpu.png | Bin 1466 -> 635 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/cpu.png b/ground/openpilotgcs/src/plugins/coreplugin/images/cpu.png index d5b42c728447b2cc744ed7c429aa3ef68e50af53..37e9794222d91f6a4e1dc4d92a6be77f06a6e4d9 100644 GIT binary patch delta 574 zcmV-E0>S;d3;P6+NPhwyNkl_0DEG|_16iQd(!uqKQ2CR`{EEq#NT0@%5WSsND zOdBjnE?n+=_nvd+zWd&Y&~WG)fIc*D@9iu0IUP0h+ZWTxqkl6GVVdTDS^0b(_XiI^ zA2}kp*E|7nczP0=rlC+MU}$qYa=F~Pk#*vTC$BExKp2LBTCJu4iIo=2znaHhv$G*G z&pL6$lScs_LD;s9{jqNJwzuKJrRR`;B=#MjfW&HK{`&9`<~A&2s<;?*pu?^U-1#_* zh1ms2OClbRgMT^SbX`X_n?)*p7hOBM5RFDbo;rf-xJuwqJb{_hrxdYND#5a>z`19h zb>g@tuik-omTI+%iBE4al70lkHc&2?mHQ@yP^8_XHxSzqgOoCuf#$WMRVo#vI(sm6 z;uyI01=c$AtP{sIdBF_W!M)EPaCPzpTC1&a97lcCH-GMlN#44Rj=l~=B9UMQ!4MB_ z-G<&R+j0K&G%}gYKM%+>S}>N}gSky5Jp1)yb%?&egYRE(=IcvbK05$0DDd=Vsv$DZ zI&tcT0)Yxdu~<}XhQndJ3H^plNId@etsyecI&s94SHDKf6=U7I)S!6ZPnH%HaJ|Sn zam16SZZ`-$7)KlWoBkJ<@y^Y-C#ka0bMJ8@)CAq}e93j)mA?WE0Cg}mJ8n)E00000 M07*qoM6N<$f-iUu=l}o! literal 1466 zcmeAS@N?(olHy`uVBq!ia0vp^0wB!61|;P_|4#%`k|nMYCBgY=CFO}lsSJ)O`AMk? zp1FzXsX?iUDV2pMQ*9U+n3Xa^B1$5BeXNr6bM+EIYV;~{3xK*A7;Nk-3KEmEQ%e+* zQqwc@Y?a>c-mj#PnPRIHZt82`Ti~3Uk?B!Ylp0*+7m{3+ootz+WN)WnQ(*-(AUCxn zQK2F?C$HG5!d3}vt`(3C64qBz04piUwpD^SD#ABF!8yMuRl!uxKsVXI%uvD1M9IxIyg#@@$ndN=gc>^!3Zj z%k|2Q_413-^$jg8E%gnI^o@*kfhu&1EAvVcD|GXUm0>2hq!uR^WfqiV=I1GZOiWD5 zFD$Tv3bSNU;+l1ennz|zM-B0$V)JVzP|XC=H|jx7ncO3BHWAB;NpiyW)Z+ZoqGVvir744~DzI`cN=+=uFAB-e&w+(vKt_H^esM;Afr4|esh*)icxGNo zet9uiy|1s8XI^nhVqS8pr;Du;&;-5A%oHm(M?+^z3kxF`OEWh^Lsvr!M+;*|S7T!n zAk)pn$r+~CB|o_|H#M&WrZ)wl*BGZ>P*TV(0NU)5T9jFqn&MWJpQ`}&vQ;K-w;13w z52`l>w_6Nx>eUB2MjsThND&Pa0;V1i6P|2=9C*S{%>$7Xs4l*cz<_=dd|ByMHtP!^rnr^sH3N0>8tKT20LI%z{de z8m>yF-Em#hqJGcY`XJ_=>-*NzwgndLd%thrcRVUu$mv17+)sb$`1trF6RCwUddb<@ z+;#iq^RMKrq7Jhtx*p@eiRH35BE@;{G!C_#n-AIfBvwD@7TXzd}Rn%^FfA-8B-cJ-{d*{ zR48TQrWMy;$DDXu_W9S>ucr6z-CIyLkGRc(hAW%$^g7775p zld}2d86UUBg6r3>f75+n`}XZCu4bJ`G2+QHk-8(ArON7&YdX_s!b&Svmp41Pc``{6&KGwWx&sG5BI^y$#v zwINy({m18Y&gy;jGyGZa;x$|R1tMm0r!8Y*QA*o=S1)&$advs5p5WF=ITu!6&AP64 iA)fos>(9;&j0`SW-gd8MTzdg3O+8)xT-G@yGywoP@+5r# From 62bbe208afb24788a5462a8e3bd5beb9858fa509 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 29 Jul 2012 15:10:30 +0100 Subject: [PATCH 102/543] GCS-Fixes wrong flight mode settings --- .../src/plugins/config/configinputwidget.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index 78f32055b..bbd56a583 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -94,12 +94,12 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent) connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack())); m_config->stackedWidget->setCurrentIndex(0); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,1); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,2); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,3); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,1); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,2); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,3); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,3); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,4); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,5); addUAVObjectToWidgetRelation("ManualControlSettings","FlightModeNumber",m_config->fmsPosNum); addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Roll,"Roll"); From ca22b54b86b6a7acce755b81a3fa9cac52a85560 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Mon, 30 Jul 2012 06:28:40 +1000 Subject: [PATCH 103/543] Change dates on copyright --- ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h | 2 +- ground/openpilotgcs/src/plugins/coreplugin/versiondialog.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h b/ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h index 3398a3c89..c7a1db3b4 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h @@ -47,7 +47,7 @@ const char * const GCS_VERSION_CODENAME = "Pascal"; const char * const GCS_VERSION_LONG = GCS_VERSION; const char * const GCS_AUTHOR = "OpenPilot Project"; -const char * const GCS_YEAR = "2011"; +const char * const GCS_YEAR = "2012"; const char * const GCS_HELP = "http://wiki.openpilot.org"; #ifdef GCS_REVISION diff --git a/ground/openpilotgcs/src/plugins/coreplugin/versiondialog.cpp b/ground/openpilotgcs/src/plugins/coreplugin/versiondialog.cpp index aa8239f6e..1fbb3b1b9 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/versiondialog.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/versiondialog.cpp @@ -76,7 +76,7 @@ VersionDialog::VersionDialog(QWidget *parent) "
" "%8" "
" - "Copyright 2008-%6 %7. All rights reserved.
" + "Copyright 2010-%6 %7. All rights reserved.
" "
" "This program is free software; you can redistribute it and/or modify
" "it under the terms of the GNU General Public License as published by
" From 005f08cbc2d1f856c9abf2edc761fc05e49c8e4f Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sun, 29 Jul 2012 14:51:39 -0700 Subject: [PATCH 104/543] added help buttons, removed wiki buttons, fixed input spacing, misc text fixes, tooltips, removed headings from input chan form --- .../src/plugins/config/airframe.ui | 19 +- .../src/plugins/config/camerastabilization.ui | 94 +- .../src/plugins/config/cc_hw_settings.ui | 25 +- .../src/plugins/config/ccattitude.ui | 3 + .../openpilotgcs/src/plugins/config/input.ui | 430 +- .../src/plugins/config/inputchannelform.cpp | 17 +- .../src/plugins/config/inputchannelform.ui | 514 +- .../openpilotgcs/src/plugins/config/output.ui | 3 + .../src/plugins/config/stabilization.ui | 6914 ++++++++--------- .../openpilotgcs/src/plugins/config/txpid.ui | 46 +- 10 files changed, 4113 insertions(+), 3952 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 6e61303e4..aa62479cf 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -119,8 +119,8 @@ 0 0 - 785 - 703 + 779 + 691 @@ -2755,8 +2755,8 @@ margin:1px; 0 0 - 192 - 236 + 247 + 301 @@ -3067,15 +3067,15 @@ p, li { white-space: pre-wrap; } <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;"> <table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;"> <tr> <td style="border: none;"> <p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD REQUIRES CAUTION</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;"><br /></span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</span></p> -<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</span></p></td></tr></table></body></html> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</p> +<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</p></td></tr></table></body></html>
@@ -3143,6 +3143,9 @@ p, li { white-space: pre-wrap; } 32 + + Takes you to the wiki page + diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index ff1f84049..84d876053 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -132,7 +132,7 @@ 0 0 790 - 644 + 648 @@ -153,7 +153,7 @@ 0 - 88 + 70 @@ -975,54 +975,57 @@ value.
- - - - - 0 - 0 - - - - - 32 - 32 - - - - - true - - - - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 32 - 32 - - - - Ctrl+S - - - false - - - true - - - 4 + + + + + 0 + 0 + + + + + 32 + 32 + + + + + true + + + + Takes you to the wiki page + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + Ctrl+S + + + false + + + true + + + @@ -1116,7 +1119,6 @@ Apply or Save button afterwards. pitchResponseTime yawResponseTime MaxAxisLockRate - camerastabilizationHelp camerastabilizationResetToDefaults camerastabilizationSaveRAM camerastabilizationSaveSD diff --git a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui index 08118c4b5..b9236d623 100644 --- a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui +++ b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui @@ -108,7 +108,7 @@ 0 0 547 - 651 + 679 @@ -287,14 +287,17 @@ - + Qt::Vertical + + QSizePolicy::Fixed + 20 - 328 + 20 @@ -318,6 +321,19 @@ + + + + Qt::Vertical + + + + 20 + 328 + + + + @@ -422,6 +438,9 @@ 32 + + Takes you to the wiki page + diff --git a/ground/openpilotgcs/src/plugins/config/ccattitude.ui b/ground/openpilotgcs/src/plugins/config/ccattitude.ui index c3585866b..74f70c3fa 100644 --- a/ground/openpilotgcs/src/plugins/config/ccattitude.ui +++ b/ground/openpilotgcs/src/plugins/config/ccattitude.ui @@ -316,6 +316,9 @@ arming it in that case! 32 + + Takes you to the wiki page + diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index 5fffc2773..e40e232f7 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -6,14 +6,14 @@ 0 0 - 693 - 882 + 702 + 920 Form - + @@ -107,8 +107,8 @@ 0 0 - 671 - 755 + 672 + 783 @@ -139,6 +139,357 @@ + + + + 0 + + + + + true + + + + 0 + 0 + + + + + 0 + 26 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +margin:5px; +font:bold; + + + Neutral + + + Qt::AlignCenter + + + + + + + true + + + + 0 + 0 + + + + + 42 + 26 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +margin:5px; +font:bold; + + + Rev. + + + Qt::AlignCenter + + + + + + + true + + + + 0 + 0 + + + + + 80 + 26 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +margin:5px; +font:bold; + + + Number + + + Qt::AlignCenter + + + + + + + true + + + + 0 + 0 + + + + + 45 + 26 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +margin:5px; +font:bold; + + + Min + + + Qt::AlignCenter + + + + + + + true + + + + 0 + 0 + + + + + 100 + 26 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +margin:5px; +font:bold; + + + Type + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 5 + 20 + + + + + + + + true + + + + 0 + 0 + + + + + 45 + 26 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +margin:5px; +font:bold; + + + Max + + + Qt::AlignCenter + + + + + + + true + + + + 0 + 0 + + + + + 80 + 26 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +margin:5px; +font:bold; + + + Function + + + Qt::AlignCenter + + + + + + + true + + + + 0 + 0 + + + + + 48 + 26 + + + + + 75 + false + true + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +margin:5px; +font:bold; + + + Neut. + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 2 + 20 + + + + + + @@ -153,21 +504,34 @@ 20 - 5 + 10 - + + + + Qt::Horizontal + + + + 40 + 20 + + + + + Roll/Pitch/Yaw stick deadband - + Stick deadband in percents of full range (0-10), zero to disable @@ -183,14 +547,17 @@ - - + + Qt::Horizontal + + QSizePolicy::Fixed + - 40 + 12 20 @@ -373,8 +740,8 @@ 0 0 - 508 - 770 + 540 + 510 @@ -611,23 +978,20 @@ channel value for each flight mode. - - + + Qt::Vertical - - QSizePolicy::Fixed - 20 - 50 + 100 - + @@ -636,6 +1000,12 @@ channel value for each flight mode. Configure each stabilization mode for each axis + + 0 + + + 12 + @@ -801,19 +1171,6 @@ margin:1px; - - - - Qt::Vertical - - - - 20 - 300 - - - - @@ -908,8 +1265,8 @@ margin:1px; 0 0 - 550 - 147 + 529 + 165 @@ -1072,6 +1429,9 @@ margin:1px; 32 + + Takes you to the wiki page + diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp index e80986399..fe54504d0 100644 --- a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp @@ -10,22 +10,7 @@ inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) : { ui->setupUi(this); - //The first time through the loop, keep the legend. All other times, delete it. - if(!showlegend) - { - layout()->removeWidget(ui->legend0); - layout()->removeWidget(ui->legend1); - layout()->removeWidget(ui->legend2); - layout()->removeWidget(ui->legend3); - layout()->removeWidget(ui->legend4); - layout()->removeWidget(ui->legend5); - delete ui->legend0; - delete ui->legend1; - delete ui->legend2; - delete ui->legend3; - delete ui->legend4; - delete ui->legend5; - } + connect(ui->channelMin,SIGNAL(valueChanged(int)),this,SLOT(minMaxUpdated())); connect(ui->channelMax,SIGNAL(valueChanged(int)),this,SLOT(minMaxUpdated())); diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.ui b/ground/openpilotgcs/src/plugins/config/inputchannelform.ui index d78727f9a..8a1d260f3 100644 --- a/ground/openpilotgcs/src/plugins/config/inputchannelform.ui +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.ui @@ -6,7 +6,7 @@ 0 0 - 767 + 666 59 @@ -26,7 +26,7 @@ 0 - + @@ -45,254 +45,7 @@ - - - - - 6 - 0 - - - - - 0 - 25 - - - - - 100 - 16777215 - - - - Qt::StrongFocus - - - - - - - - 0 - 25 - - - - Qt::StrongFocus - - - QAbstractSpinBox::NoButtons - - - 9999 - - - 1000 - - - - - - - - 0 - 25 - - - - Qt::StrongFocus - - - QAbstractSpinBox::NoButtons - - - 9999 - - - 1000 - - - - - - - true - - - - 0 - 0 - - - - - 0 - 26 - - - - - 75 - false - true - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -margin:5px; -font:bold; - - - Function - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - - 45 - 26 - - - - - 75 - false - true - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -margin:5px; -font:bold; - - - Max - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - - 0 - 26 - - - - - 75 - false - true - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -margin:5px; -font:bold; - - - Min - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - - 0 - 26 - - - - - 75 - false - true - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -margin:5px; -font:bold; - - - Neutral - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - Qt::StrongFocus - - - Qt::Horizontal - - - - + @@ -320,20 +73,7 @@ font:bold; - - - - true - - - - 0 - 0 - - - - - + false @@ -345,11 +85,90 @@ font:bold; - Rev + - + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 20 + + + + + + + + + 6 + 0 + + + + + 0 + 25 + + + + + 100 + 16777215 + + + + Qt::StrongFocus + + + + + + + + 0 + 25 + + + + Qt::StrongFocus + + + QAbstractSpinBox::NoButtons + + + 9999 + + + 1000 + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 20 + + + + + @@ -374,84 +193,45 @@ font:bold; - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 20 - - - - - - - - true - - - - 0 - 0 - - - - - 0 - 26 - - - - - 75 - false - true - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -margin:5px; -font:bold; - - - Type - - - Qt::AlignCenter - - - - + true + + + 0 + 0 + + + + + + + + + 0 + 25 + + + + Qt::StrongFocus + + + QAbstractSpinBox::NoButtons + + + 9999 + + + 1000 + + + + + - + 0 0 @@ -459,31 +239,49 @@ font:bold; 0 - 26 + 22 - - - 75 - false - true - + + Qt::StrongFocus - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -margin:5px; -font:bold; - - - Number - - - Qt::AlignCenter + + Qt::Horizontal + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 15 + 20 + + + + diff --git a/ground/openpilotgcs/src/plugins/config/output.ui b/ground/openpilotgcs/src/plugins/config/output.ui index de33805a6..dbddcda3b 100644 --- a/ground/openpilotgcs/src/plugins/config/output.ui +++ b/ground/openpilotgcs/src/plugins/config/output.ui @@ -971,6 +971,9 @@ margin:1px; 32 + + Takes you to the wiki page + diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 97434d7f1..4d7254ac6 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -454,10 +454,7 @@ - 12 - - - 12 + -1 @@ -600,15 +597,3315 @@ 0 0 - 758 - 806 + 756 + 819 - - - 6 - - + + + + + + 0 + 0 + + + + + 0 + 200 + + + + + 16777215 + 181 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + Attitude Stabilization (Outer Loop) + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + 4 + + + + + + 0 + 0 + + + + Qt::StrongFocus + + + + + + Link Roll and Pitch + + + + + + + Qt::Horizontal + + + QSizePolicy::MinimumExpanding + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + Reset all values to GCS defaults + + + + + + Default + + + + button:default + buttongroup:2 + + + + + + + + + + + 0 + 0 + + + + + 0 + 131 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 78 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + @@ -619,7 +3916,7 @@ 0 - 181 + 200 @@ -639,7 +3936,7 @@ 6 - + 4 @@ -678,46 +3975,6 @@ - - - - - 0 - 0 - - - - - 51 - 25 - - - - - 16777215 - 16777215 - - - - Takes you to the online wiki page for Rate settings - - - false - - - - - - Wiki - - - - button:help - url:http://wiki.openpilot.org/display/Doc/Stabilization+panel - - - - @@ -3505,656 +6762,67 @@ value as the Kp. - - - - - 0 - 0 - + + + + Qt::Vertical + + QSizePolicy::Preferred + + + + 20 + 180 + + + + + + 0 - 181 + 80 - - - 16777215 - 181 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - Attitude Stabilization (Outer Loop) + - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - + - - - 4 + + + + 0 + 0 + - - - - - 0 - 0 - - - - Qt::StrongFocus - - - - - - Link Roll and Pitch - - - - - - - Qt::Horizontal - - - QSizePolicy::MinimumExpanding - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 51 - 25 - - - - Takes you to the online wiki page for Attitude settings - - - - - - Wiki - - - - button:help - url:http://wiki.openpilot.org/display/Doc/Stabilization+panel - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - Reset all values to GCS defaults - - - - - - Default - - - - button:default - buttongroup:2 - - - - - + + + 300 + 20 + + + + When the throttle is low, zero the intergral term to prevent intergral wind-up + + + + + + Zero the integral when throttle is low + + + + objname:StabilizationSettings + fieldname:LowThrottleZeroIntegral + + + - + 0 @@ -4163,2683 +6831,26 @@ value as the Kp. - 0 - 131 + 136 + 20 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false + + If you check this, the GCS will udpate the stabilization factors +automatically every 300ms, which will help for fast tuning. - - + + Update in real time - - true - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 78 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - + @@ -6850,7 +6861,7 @@ border-radius: 5; 0 - 211 + 230 @@ -7381,7 +7392,7 @@ border-radius: 5; - + 4 @@ -7401,37 +7412,6 @@ border-radius: 5; - - - - - 0 - 0 - - - - - 51 - 25 - - - - Takes you to the online wiki page for Stick settings - - - - - - Wiki - - - - button:help - url:http://wiki.openpilot.org/display/Doc/Stabilization+panel - - - - @@ -10463,90 +10443,18 @@ Attitude
- - - - - 0 - 80 - - - - - - - - - - - 0 - 0 - - - - - 300 - 20 - - - - When the throttle is low, zero the intergral term to prevent intergral wind-up - - - - - - Zero the integral when throttle is low - - - - objname:StabilizationSettings - fieldname:LowThrottleZeroIntegral - - - - - - - - - 0 - 0 - - - - - 136 - 20 - - - - If you check this, the GCS will udpate the stabilization factors -automatically every 300ms, which will help for fast tuning. - - - - - - Update in real time - - - - - - - - + + Qt::Vertical - QSizePolicy::Preferred + QSizePolicy::Fixed - 20 - 180 + 10 + 12 @@ -10645,18 +10553,15 @@ automatically every 300ms, which will help for fast tuning. 0 0 - 758 - 806 + 470 + 745 true - - - 6 - - + + @@ -14114,7 +14019,7 @@ value as the Kp. - + @@ -17380,7 +17285,7 @@ border-radius: 5; - + @@ -20666,7 +20571,7 @@ rate(deg/s) - + @@ -24089,6 +23994,56 @@ border-radius: 5; 4 + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 32 + 32 + + + + Takes you to the wiki page + + + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + true + + + + button:help + url:http://wiki.openpilot.org/display/Doc/Stabilization+panel + + + + @@ -24198,7 +24153,6 @@ Useful if you have accidentally changed some settings. scrollArea checkBox_7 - pushButton_19 pushButton_20 horizontalSlider_76 spinBox_7 @@ -24213,7 +24167,6 @@ Useful if you have accidentally changed some settings. horizontalSlider_81 spinBox_10 checkBox_8 - pushButton_21 pushButton_22 horizontalSlider_82 spinBox_13 @@ -24227,7 +24180,6 @@ Useful if you have accidentally changed some settings. spinBox_19 horizontalSlider_87 spinBox_20 - pushButton_23 pushButton_24 horizontalSlider_88 spinBox_16 @@ -24291,6 +24243,8 @@ Useful if you have accidentally changed some settings. AccelKp AccelKi - + + + diff --git a/ground/openpilotgcs/src/plugins/config/txpid.ui b/ground/openpilotgcs/src/plugins/config/txpid.ui index e9acbec2d..dfb430906 100644 --- a/ground/openpilotgcs/src/plugins/config/txpid.ui +++ b/ground/openpilotgcs/src/plugins/config/txpid.ui @@ -14,9 +14,6 @@ TxPID - - 12 - @@ -111,7 +108,7 @@ 0 0 678 - 683 + 678 @@ -144,7 +141,7 @@ Up to 3 separate PID options (or option pairs) can be selected and updated. - After enabling the module, you must power cycle before using and configuring. + After enabling you must power cycle your board before using and configuring @@ -688,6 +685,41 @@ margin:1px; + + + + + 32 + 32 + + + + Takes you to the wiki page + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + true + + + + button:help + url:http://wiki.openpilot.org/display/Doc/TxPID+Module + + + + @@ -756,6 +788,8 @@ margin:1px; ThrottleMax UpdateMode - + + + From ef04025d055b20ee9f322dde8cb9567d060eab92 Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sun, 29 Jul 2012 15:14:40 -0700 Subject: [PATCH 105/543] couple small sizing issues in stabi, and spacer in hw settings --- .../src/plugins/config/cc_hw_settings.ui | 6 +++--- .../src/plugins/config/stabilization.ui | 16 ++++++++-------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui index b9236d623..a7f78b623 100644 --- a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui +++ b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui @@ -107,8 +107,8 @@ 0 0 - 547 - 679 + 562 + 567 @@ -329,7 +329,7 @@ 20 - 328 + 25 diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 4d7254ac6..22175d84c 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -613,7 +613,7 @@ 0 - 200 + 195 @@ -3916,7 +3916,7 @@ border-radius: 5; 0 - 200 + 195 @@ -6861,7 +6861,7 @@ automatically every 300ms, which will help for fast tuning. 0 - 230 + 225 @@ -10553,8 +10553,8 @@ Attitude 0 0 - 470 - 745 + 756 + 819 @@ -10572,7 +10572,7 @@ Attitude 0 - 220 + 230 @@ -14030,7 +14030,7 @@ value as the Kp. 0 - 190 + 200 @@ -17296,7 +17296,7 @@ border-radius: 5; 0 - 211 + 230 From 9ab86f7c7e187bcdd79572e9fa7f840402628867 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 29 Jul 2012 23:29:39 +0100 Subject: [PATCH 106/543] GCS-Changed "wiki" help buttons to the standard ones. Updated the links to tiny links. --- .../src/plugins/config/camerastabilization.ui | 10 +- .../plugins/config/config_cc_hw_widget.cpp | 2 +- .../configcamerastabilizationwidget.cpp | 7 +- .../config/configcamerastabilizationwidget.h | 1 - .../plugins/config/configccattitudewidget.cpp | 2 +- .../src/plugins/config/configinputwidget.cpp | 2 +- .../src/plugins/config/configoutputwidget.cpp | 2 +- .../plugins/config/configpipxtremewidget.cpp | 2 +- .../src/plugins/config/configtxpidwidget.cpp | 2 +- .../config/configvehicletypewidget.cpp | 2 +- .../src/plugins/config/pipxtreme.ui | 30 +++- .../src/plugins/config/stabilization.ui | 141 ++++-------------- .../openpilotgcs/src/plugins/config/txpid.ui | 34 ++++- .../plugins/uploader/uploadergadgetwidget.cpp | 2 +- 14 files changed, 109 insertions(+), 130 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index ff1f84049..b6278364d 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -131,8 +131,8 @@ 0 0 - 790 - 644 + 792 + 630 @@ -1016,6 +1016,12 @@ value. true + + + button:help + url:http://wiki.openpilot.org/x/cACrAQ + + diff --git a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp index 89b752996..9011b07b4 100644 --- a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp @@ -128,7 +128,7 @@ void ConfigCCHWWidget::widgetsContentsChanged() void ConfigCCHWWidget::openHelp() { - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/CopterControl+HW+Settings", QUrl::StrictMode) ); + QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/D4AUAQ", QUrl::StrictMode) ); } /** diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index c15af11b2..a6874c0c4 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -95,7 +95,7 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent connect(m_camerastabilization->camerastabilizationResetToDefaults, SIGNAL(clicked()), this, SLOT(resetToDefaults())); connect(m_camerastabilization->camerastabilizationSaveRAM, SIGNAL(clicked()), this, SLOT(applySettings())); connect(m_camerastabilization->camerastabilizationSaveSD, SIGNAL(clicked()), this, SLOT(saveSettings())); - connect(m_camerastabilization->camerastabilizationHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + autoLoadWidgets(); disableMouseWheelEvents(); } @@ -333,11 +333,6 @@ void ConfigCameraStabilizationWidget::resetToDefaults() refreshUIValues(defaults); } -void ConfigCameraStabilizationWidget::openHelp() -{ - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Camera+Stabilization+Configuration", QUrl::StrictMode) ); -} - void ConfigCameraStabilizationWidget::enableControls(bool enable) { m_camerastabilization->camerastabilizationResetToDefaults->setEnabled(enable); diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h index 743435adb..8e1305268 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h @@ -47,7 +47,6 @@ private: void refreshUIValues(CameraStabSettings::DataFields &cameraStabData); private slots: - void openHelp(); void resetToDefaults(); void applySettings(); void saveSettings(); diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp index 044dd7770..e24ea74eb 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp @@ -169,7 +169,7 @@ void ConfigCCAttitudeWidget::startAccelCalibration() { void ConfigCCAttitudeWidget::openHelp() { - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/CopterControl+Attitude+Configuration", QUrl::StrictMode) ); + QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/44Cf", QUrl::StrictMode) ); } void ConfigCCAttitudeWidget::enableControls(bool enable) diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index bbd56a583..5e3f3dd9d 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -290,7 +290,7 @@ void ConfigInputWidget::resizeEvent(QResizeEvent *event) void ConfigInputWidget::openHelp() { - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Input+Configuration", QUrl::StrictMode) ); + QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/04Cf", QUrl::StrictMode) ); } void ConfigInputWidget::goToWizard() { diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index 2f77d58c1..af91c677e 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -371,7 +371,7 @@ void ConfigOutputWidget::updateObjectsFromWidgets() void ConfigOutputWidget::openHelp() { - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Output+Configuration", QUrl::StrictMode) ); + QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/WIGf", QUrl::StrictMode) ); } void ConfigOutputWidget::stopTests() diff --git a/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp b/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp index 7808b6dfa..887184cfa 100644 --- a/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp @@ -52,7 +52,7 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget } else { qDebug() << "Error: Object is unknown (PipXSettings)."; } - + autoLoadWidgets(); addApplySaveButtons(m_pipx->Apply, m_pipx->Save); addUAVObjectToWidgetRelation("PipXSettings", "TelemetryConfig", m_pipx->TelemPortConfig); diff --git a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp index 6c6ac1c9a..621577b20 100644 --- a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp @@ -40,7 +40,7 @@ ConfigTxPIDWidget::ConfigTxPIDWidget(QWidget *parent) : ConfigTaskWidget(parent) Core::Internal::GeneralSettings * settings=pm->getObject(); if(!settings->useExpertMode()) m_txpid->Apply->setVisible(false); - + autoLoadWidgets(); addApplySaveButtons(m_txpid->Apply, m_txpid->Save); // Cannot use addUAVObjectToWidgetRelation() for OptionaModules enum because diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index e91d08574..fcce79a49 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -752,7 +752,7 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets() void ConfigVehicleTypeWidget::openHelp() { - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Airframe+configuration", QUrl::StrictMode) ); + QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/44Cf", QUrl::StrictMode) ); } /** diff --git a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui index 9de1a7120..2f7068c4f 100644 --- a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui +++ b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui @@ -86,6 +86,32 @@ + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + true + + + + button:help + url:http://wiki.openpilot.org/x/dACrAQ + + + + @@ -1752,6 +1778,8 @@ Apply Save - + + + diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 97434d7f1..5293e60aa 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -639,7 +639,7 @@ 6 - + 4 @@ -678,46 +678,6 @@ - - - - - 0 - 0 - - - - - 51 - 25 - - - - - 16777215 - 16777215 - - - - Takes you to the online wiki page for Rate settings - - - false - - - - - - Wiki - - - - button:help - url:http://wiki.openpilot.org/display/Doc/Stabilization+panel - - - - @@ -4050,7 +4010,7 @@ value as the Kp. - + 4 @@ -4089,37 +4049,6 @@ value as the Kp. - - - - - 0 - 0 - - - - - 51 - 25 - - - - Takes you to the online wiki page for Attitude settings - - - - - - Wiki - - - - button:help - url:http://wiki.openpilot.org/display/Doc/Stabilization+panel - - - - @@ -7381,7 +7310,7 @@ border-radius: 5; - + 4 @@ -7401,37 +7330,6 @@ border-radius: 5; - - - - - 0 - 0 - - - - - 51 - 25 - - - - Takes you to the online wiki page for Stick settings - - - - - - Wiki - - - - button:help - url:http://wiki.openpilot.org/display/Doc/Stabilization+panel - - - - @@ -24089,6 +23987,32 @@ border-radius: 5; 4 + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + true + + + + button:help + url:http://wiki.openpilot.org/x/DAO9 + + + + @@ -24198,7 +24122,6 @@ Useful if you have accidentally changed some settings. scrollArea checkBox_7 - pushButton_19 pushButton_20 horizontalSlider_76 spinBox_7 @@ -24213,7 +24136,6 @@ Useful if you have accidentally changed some settings. horizontalSlider_81 spinBox_10 checkBox_8 - pushButton_21 pushButton_22 horizontalSlider_82 spinBox_13 @@ -24227,7 +24149,6 @@ Useful if you have accidentally changed some settings. spinBox_19 horizontalSlider_87 spinBox_20 - pushButton_23 pushButton_24 horizontalSlider_88 spinBox_16 @@ -24291,6 +24212,8 @@ Useful if you have accidentally changed some settings. AccelKp AccelKi - + + + diff --git a/ground/openpilotgcs/src/plugins/config/txpid.ui b/ground/openpilotgcs/src/plugins/config/txpid.ui index e9acbec2d..3d7bf7d97 100644 --- a/ground/openpilotgcs/src/plugins/config/txpid.ui +++ b/ground/openpilotgcs/src/plugins/config/txpid.ui @@ -110,8 +110,8 @@ 0 0 - 678 - 683 + 686 + 673 @@ -688,6 +688,32 @@ margin:1px; + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + true + + + + button:help + url:http://wiki.openpilot.org/x/DACiAQ + + + + @@ -756,6 +782,8 @@ margin:1px; ThrottleMax UpdateMode - + + + diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp index a692433b1..d5d82c13e 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp @@ -685,5 +685,5 @@ void UploaderGadgetWidget::versionMatchCheck() void UploaderGadgetWidget::openHelp() { - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Uploader+Plugin", QUrl::StrictMode) ); + QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/AoBZ", QUrl::StrictMode) ); } From 0874b3db62d98b388e40d98e640b71fd378b32ee Mon Sep 17 00:00:00 2001 From: Kenz Dale Date: Mon, 30 Jul 2012 13:37:56 +0200 Subject: [PATCH 107/543] Fixed GPS position to include gps heading. --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 34 ++++++------------- .../src/plugins/opmap/opmapgadgetwidget.h | 1 - 2 files changed, 10 insertions(+), 25 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index abc51de20..c0069dac9 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -48,6 +48,7 @@ #include "positionactual.h" #include "homelocation.h" +#include "gpsposition.h" #define allow_manual_home_location_move @@ -662,15 +663,17 @@ void OPMapGadgetWidget::updatePosition() uav_pos = internals::PointLatLng(uav_latitude, uav_longitude); // ************* - // get the current GPS details + // get current GPS position + ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager* objManager = pm->getObject(); - // get current GPS position - if (!getGPSPosition(gps_latitude, gps_longitude, gps_altitude)) - return; + GPSPosition *gpsPositionData = GPSPosition::GetInstance(objManager); // get current GPS heading -// gps_heading = getGPS_Heading(); - gps_heading = 0; + gps_heading = gpsPositionData->getData().Heading; + gps_latitude = gpsPositionData->getData().Latitude; + gps_longitude = gpsPositionData->getData().Longitude; + gps_altitude = gpsPositionData->getData().Altitude; gps_pos = internals::PointLatLng(gps_latitude, gps_longitude); @@ -698,7 +701,7 @@ void OPMapGadgetWidget::updatePosition() m_map->GPS->SetUAVPos(gps_pos, gps_altitude); // set the maps GPS position m_map->GPS->SetUAVHeading(gps_heading); // set the maps GPS heading - // ************* + // ************* } /** @@ -2387,25 +2390,8 @@ double OPMapGadgetWidget::getUAV_Yaw() return yaw; } -bool OPMapGadgetWidget::getGPSPosition(double &latitude, double &longitude, double &altitude) -{ - double LLA[3]; - - if (!obum) - return false; - - if (obum->getGPSPosition(LLA) < 0) - return false; // error - - latitude = LLA[0]; - longitude = LLA[1]; - altitude = LLA[2]; - - return true; -} // ************************************************************************************* - void OPMapGadgetWidget::setMapFollowingMode() { if (!m_widget || !m_map) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 24f638a80..d815bf9aa 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -350,7 +350,6 @@ private: internals::PointLatLng destPoint(internals::PointLatLng source, double bear, double dist); bool getUAVPosition(double &latitude, double &longitude, double &altitude); - bool getGPSPosition(double &latitude, double &longitude, double &altitude); double getUAV_Yaw(); void setMapFollowingMode(); From b997a4a7fe594a6f7cd71d062e946eb33b508a58 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Mon, 30 Jul 2012 21:58:36 +1000 Subject: [PATCH 108/543] Make connect button use onclicked() signal rather than onpressed() --- .../src/plugins/coreplugin/connectionmanager.cpp | 6 +++--- .../openpilotgcs/src/plugins/coreplugin/connectionmanager.h | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp index f49d98c0e..eb3db6d50 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp @@ -81,7 +81,7 @@ ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow, QTabWidge // modeStack->insertCornerWidget(modeStack->cornerWidgetCount()-1, this); modeStack->setCornerWidget(this, Qt::TopRightCorner); - QObject::connect(m_connectBtn, SIGNAL(pressed()), this, SLOT(onConnectPressed())); + QObject::connect(m_connectBtn, SIGNAL(clicked()), this, SLOT(onConnectClicked())); } ConnectionManager::~ConnectionManager() @@ -224,9 +224,9 @@ void ConnectionManager::onConnectionDestroyed(QObject *obj) // Pip } /** -* Slot called when the user pressed the connect/disconnect button +* Slot called when the user clicks the connect/disconnect button */ -void ConnectionManager::onConnectPressed() +void ConnectionManager::onConnectClicked() { // Check if we have a ioDev already created: if (!m_ioDev) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h index 289e65590..90f779aed 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h @@ -93,7 +93,7 @@ private slots: void objectAdded(QObject *obj); void aboutToRemoveObject(QObject *obj); - void onConnectPressed(); + void onConnectClicked(); void devChanged(IConnection *connection); // void onConnectionClosed(QObject *obj); From 31a788e44e85a67d2645c8525cef42349a1fc7ea Mon Sep 17 00:00:00 2001 From: David Ankers Date: Mon, 30 Jul 2012 22:28:28 +1000 Subject: [PATCH 109/543] Change the icon to go to the system page, icon is still wrong but now at least the button works. --- ground/openpilotgcs/src/plugins/welcome/qml/main.qml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/welcome/qml/main.qml b/ground/openpilotgcs/src/plugins/welcome/qml/main.qml index a2362d3e2..fea4b253b 100644 --- a/ground/openpilotgcs/src/plugins/welcome/qml/main.qml +++ b/ground/openpilotgcs/src/plugins/welcome/qml/main.qml @@ -63,7 +63,7 @@ Rectangle { WelcomePageButton { baseIconName: "planner" label: "Flight Planner" - onClicked: welcomePlugin.openPage("Flight Planner") + onClicked: welcomePlugin.openPage("System") } WelcomePageButton { From bb66dc95358937626060c26444be5646de9abca6 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Mon, 30 Jul 2012 14:53:57 +0100 Subject: [PATCH 110/543] GCS- Made the importexport dialog close when GCS closes. --- .../uavsettingsimportexport/uavsettingsimportexportfactory.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp index 9c0088efa..bc10d9143 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp @@ -133,7 +133,7 @@ void UAVSettingsImportExportFactory::importUAVSettings() // We are now ok: setup the import summary dialog & update it as we // go along. - ImportSummaryDialog swui; + ImportSummaryDialog swui((QWidget*)Core::ICore::instance()->mainWindow()); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); From b15091feade1027b3511a7805a29313192bc014c Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Mon, 30 Jul 2012 16:11:36 +0100 Subject: [PATCH 111/543] GCS - Made the GCS compile without OSG support --- .../openpilotgcs/src/plugins/pfdqml/pfdqml.pro | 16 ++++++++++++---- .../src/plugins/pfdqml/pfdqmlgadgetwidget.cpp | 6 ++++-- 2 files changed, 16 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro b/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro index 7064f8a0c..1b2fe8832 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro @@ -3,31 +3,39 @@ TARGET = PfdQml QT += svg QT += opengl QT += declarative +#DEFINES += USE_OSG include(../../openpilotgcsplugin.pri) include(../../plugins/coreplugin/coreplugin.pri) include(pfdqml_dependencies.pri) + +contains(DEFINES,USE_OSG){ LIBS += -losg -losgUtil -losgViewer -losgQt -losgDB -lOpenThreads -losgGA LIBS += -losgEarth -losgEarthFeatures -losgEarthUtil - +} HEADERS += \ pfdqmlplugin.h \ pfdqmlgadget.h \ pfdqmlgadgetwidget.h \ pfdqmlgadgetfactory.h \ pfdqmlgadgetconfiguration.h \ - pfdqmlgadgetoptionspage.h \ + pfdqmlgadgetoptionspage.h +contains(DEFINES,USE_OSG){ + \ osgearth.h - +} SOURCES += \ pfdqmlplugin.cpp \ pfdqmlgadget.cpp \ pfdqmlgadgetfactory.cpp \ pfdqmlgadgetwidget.cpp \ pfdqmlgadgetconfiguration.cpp \ - pfdqmlgadgetoptionspage.cpp \ + pfdqmlgadgetoptionspage.cpp +contains(DEFINES,USE_OSG){ + \ osgearth.cpp +} OTHER_FILES += PfdQml.pluginspec diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp index 311f106a5..d6e43e70e 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp @@ -19,8 +19,9 @@ #include "uavobjectmanager.h" #include "uavobject.h" #include "utils/svgimageprovider.h" +#ifdef USE_OSG #include "osgearth.h" - +#endif #include #include #include @@ -66,8 +67,9 @@ PfdQmlGadgetWidget::PfdQmlGadgetWidget(QWidget *parent) : //to expose settings values engine()->rootContext()->setContextProperty("qmlWidget", this); - +#ifdef USE_OSG qmlRegisterType("org.OpenPilot", 1, 0, "OsgEarth"); +#endif } PfdQmlGadgetWidget::~PfdQmlGadgetWidget() From 574fbe2fd910ff1e9fab3ebbae9c5fb80e0d6e19 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Tue, 31 Jul 2012 02:50:41 +1000 Subject: [PATCH 112/543] Copy one file at a time with cp --- ground/openpilotgcs/src/app/app.pro | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/app/app.pro b/ground/openpilotgcs/src/app/app.pro index e66f3f4f0..82283d3aa 100644 --- a/ground/openpilotgcs/src/app/app.pro +++ b/ground/openpilotgcs/src/app/app.pro @@ -5,9 +5,7 @@ TEMPLATE = app TARGET = $$GCS_APP_TARGET DESTDIR = $$GCS_APP_PATH QT += xml - SOURCES += main.cpp - include(../rpath.pri) include(../libs/utils/utils.pri) @@ -31,7 +29,11 @@ win32 { OTHER_FILES += openpilotgcs.rc -style_copy.commands += $(COPY_FILE) $$targetPath(\"$$GCS_SOURCE_TREE/src/app/stylesheets/*.qss\") $$targetPath(\"$$GCS_APP_PATH\") $$addNewline() +PLATFORMS = windows macos linux + +for(platform, PLATFORMS) { + style_copy.commands += $(COPY_FILE) $$targetPath(\"$$GCS_SOURCE_TREE/src/app/stylesheets/$$platform.qss\") $$targetPath(\"$$GCS_APP_PATH\") $$addNewline() + style_copy.target = FORCE QMAKE_EXTRA_TARGETS += style_copy From c93cfc5d50d4afc3a3c76a018a614d5dd4f4dd61 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Tue, 31 Jul 2012 04:11:33 +1000 Subject: [PATCH 113/543] Fixed qmake copy of qss by borrowing code from Oleg who has a better handle on qmake than I guess I ever will. --- ground/openpilotgcs/src/app/app.pro | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/app/app.pro b/ground/openpilotgcs/src/app/app.pro index 82283d3aa..ea53c1bd9 100644 --- a/ground/openpilotgcs/src/app/app.pro +++ b/ground/openpilotgcs/src/app/app.pro @@ -29,10 +29,13 @@ win32 { OTHER_FILES += openpilotgcs.rc -PLATFORMS = windows macos linux +STYLESHEETS = windows.qss \ + macos.qss \ + linux.qss -for(platform, PLATFORMS) { - style_copy.commands += $(COPY_FILE) $$targetPath(\"$$GCS_SOURCE_TREE/src/app/stylesheets/$$platform.qss\") $$targetPath(\"$$GCS_APP_PATH\") $$addNewline() +for(qss, STYLESHEETS) { + style_copy.commands += $(COPY_FILE) $$targetPath(\"$$GCS_SOURCE_TREE/src/app/stylesheets/$$qss\") $$targetPath(\"$$GCS_APP_PATH/$$qss\") $$addNewline() +} style_copy.target = FORCE QMAKE_EXTRA_TARGETS += style_copy From b490fdb6e91032f3cffe281ccd81a4ec9635e5e3 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 30 Jul 2012 14:30:03 -0700 Subject: [PATCH 114/543] Resolve build errors: add Q_DECL_EXPORT to SvgImageProvider; change unsetenv to qputenv. --- ground/openpilotgcs/src/libs/utils/svgimageprovider.h | 2 +- ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/libs/utils/svgimageprovider.h b/ground/openpilotgcs/src/libs/utils/svgimageprovider.h index 50fd0f7bb..8b11e512f 100644 --- a/ground/openpilotgcs/src/libs/utils/svgimageprovider.h +++ b/ground/openpilotgcs/src/libs/utils/svgimageprovider.h @@ -33,7 +33,7 @@ #include #include -class SvgImageProvider : public QObject, public QDeclarativeImageProvider +class Q_DECL_EXPORT SvgImageProvider : public QObject, public QDeclarativeImageProvider { Q_OBJECT public: diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp index 93427446c..89d0b852d 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp @@ -52,6 +52,7 @@ void PfdQmlGadget::loadConfiguration(IUAVGadgetConfiguration* config) qputenv("OSGEARTH_CACHE_ONLY", "true"); } else { //how portable it is? - unsetenv("OSGEARTH_CACHE_ONLY"); + //unsetenv("OSGEARTH_CACHE_ONLY"); + qputenv("OSGEARTH_CACHE_ONLY", "false"); } } From 6adafbc4bf4cc0e38972304129059a1ccadc9582 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 30 Jul 2012 14:45:56 -0700 Subject: [PATCH 115/543] PopupWidget, Bugfix: put the mixer back into the frame at the same size it started from; keeps it from oversetting neighbors when the dialog is closed. --- .../src/plugins/uavobjectwidgetutils/popupwidget.cpp | 4 ++++ .../src/plugins/uavobjectwidgetutils/popupwidget.h | 2 ++ 2 files changed, 6 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp index ca1af389b..71630177b 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp @@ -37,6 +37,9 @@ void PopupWidget::setWidget(QWidget* widget) m_widget = widget; m_widgetParent = widget->parentWidget(); + m_widgetWidth = m_widget->width(); + m_widgetHeight = m_widget->height(); + m_layout->addWidget(m_widget); } @@ -59,6 +62,7 @@ void PopupWidget::closePopup() if (m_widget && m_widgetParent) { if(QGroupBox * w =qobject_cast(m_widgetParent)) { + m_widget->resize(m_widgetWidth, m_widgetHeight); w->layout()->addWidget(m_widget); } } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h index a19a6650c..55f19956d 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h @@ -37,6 +37,8 @@ private: QWidget* m_widget; QWidget* m_widgetParent; QPushButton* m_closeButton; + int m_widgetWidth; + int m_widgetHeight; }; #endif // POPUPWIDGET_H From 5398d96839bc7fb986d14f3d207a6c4561661af2 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 30 Jul 2012 15:02:18 -0700 Subject: [PATCH 116/543] PopupWidget: Start the dialog at twice the size of the embedded widget. --- .../src/plugins/uavobjectwidgetutils/popupwidget.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp index 71630177b..94190cd09 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp @@ -37,9 +37,12 @@ void PopupWidget::setWidget(QWidget* widget) m_widget = widget; m_widgetParent = widget->parentWidget(); + // save the current width,height so we can restore when closed m_widgetWidth = m_widget->width(); m_widgetHeight = m_widget->height(); + // double the size of the widget for the dialog + m_widget->resize(m_widgetWidth * 2, m_widgetHeight * 2); m_layout->addWidget(m_widget); } From 5cab871ac61df54fb8dd9cb927d1f53320d04631 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 30 Jul 2012 14:45:56 -0700 Subject: [PATCH 117/543] PopupWidget, Bugfix: put the mixer back into the frame at the same size it started from; keeps it from oversetting neighbors when the dialog is closed. --- .../src/plugins/uavobjectwidgetutils/popupwidget.cpp | 4 ++++ .../src/plugins/uavobjectwidgetutils/popupwidget.h | 2 ++ 2 files changed, 6 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp index ca1af389b..71630177b 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.cpp @@ -37,6 +37,9 @@ void PopupWidget::setWidget(QWidget* widget) m_widget = widget; m_widgetParent = widget->parentWidget(); + m_widgetWidth = m_widget->width(); + m_widgetHeight = m_widget->height(); + m_layout->addWidget(m_widget); } @@ -59,6 +62,7 @@ void PopupWidget::closePopup() if (m_widget && m_widgetParent) { if(QGroupBox * w =qobject_cast(m_widgetParent)) { + m_widget->resize(m_widgetWidth, m_widgetHeight); w->layout()->addWidget(m_widget); } } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h index a19a6650c..55f19956d 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/popupwidget.h @@ -37,6 +37,8 @@ private: QWidget* m_widget; QWidget* m_widgetParent; QPushButton* m_closeButton; + int m_widgetWidth; + int m_widgetHeight; }; #endif // POPUPWIDGET_H From a306b31c9c10c2049c75e5ea4b28f48710e65d5b Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 30 Jul 2012 14:30:03 -0700 Subject: [PATCH 118/543] Resolve build errors: add Q_DECL_EXPORT to SvgImageProvider; change unsetenv to qputenv. --- ground/openpilotgcs/src/libs/utils/svgimageprovider.h | 2 +- ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/libs/utils/svgimageprovider.h b/ground/openpilotgcs/src/libs/utils/svgimageprovider.h index 50fd0f7bb..8b11e512f 100644 --- a/ground/openpilotgcs/src/libs/utils/svgimageprovider.h +++ b/ground/openpilotgcs/src/libs/utils/svgimageprovider.h @@ -33,7 +33,7 @@ #include #include -class SvgImageProvider : public QObject, public QDeclarativeImageProvider +class Q_DECL_EXPORT SvgImageProvider : public QObject, public QDeclarativeImageProvider { Q_OBJECT public: diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp index 93427446c..89d0b852d 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.cpp @@ -52,6 +52,7 @@ void PfdQmlGadget::loadConfiguration(IUAVGadgetConfiguration* config) qputenv("OSGEARTH_CACHE_ONLY", "true"); } else { //how portable it is? - unsetenv("OSGEARTH_CACHE_ONLY"); + //unsetenv("OSGEARTH_CACHE_ONLY"); + qputenv("OSGEARTH_CACHE_ONLY", "false"); } } From f5a2591d81c267f03d4fb523e934eddd3fdf3319 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Tue, 31 Jul 2012 09:03:24 +1000 Subject: [PATCH 119/543] Correct default paths for qml pfd files --- .../openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml index 363597785..801aad89b 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml @@ -1690,10 +1690,10 @@ false 2000 false - %%DATAPATH%%pfd/pfd/default/readymap.earth + %%DATAPATH%%pfd/default/readymap.earth 46.671478 10.158932 - %%DATAPATH%%pfd/pfd/default/Pfd.qml + %%DATAPATH%%pfd/default/Pfd.qml false @@ -1706,10 +1706,10 @@ false 2000 false - %%DATAPATH%%pfd/pfd/default/readymap.earth + %%DATAPATH%%pfd/default/readymap.earth 46.671478 10.158932 - %%DATAPATH%%pfd/pfd/default/Pfd.qml + %%DATAPATH%%pfd/default/Pfd.qml true From 1f7b95805e44ccde218a542752183b0141f8aaa4 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Tue, 31 Jul 2012 12:18:05 +0100 Subject: [PATCH 120/543] GCS-Added Hyper's fix to glc crashes under certain systems. --- ground/openpilotgcs/src/libs/glc_lib/glc_ext.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/glc_lib/glc_ext.cpp b/ground/openpilotgcs/src/libs/glc_lib/glc_ext.cpp index 8275a085f..ef4a32248 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/glc_ext.cpp +++ b/ground/openpilotgcs/src/libs/glc_lib/glc_ext.cpp @@ -63,7 +63,7 @@ bool glc::loadGlSlExtension() bool glc::loadPointSpriteExtension() { bool result= true; -#if !defined(Q_OS_MAC) +#if !defined(Q_OS_MAC) && !defined(Q_OS_LINUX) const QGLContext* pContext= QGLContext::currentContext(); glPointParameterf = (PFNGLPOINTPARAMETERFARBPROC)pContext->getProcAddress(QLatin1String("glPointParameterf")); if (!glPointParameterf) qDebug() << "not glPointParameterf"; From 68652ef6435e645dd6336580031386f22cfcd646 Mon Sep 17 00:00:00 2001 From: Dmytro Poplavskiy Date: Wed, 1 Aug 2012 00:32:46 +1000 Subject: [PATCH 121/543] PFD qml: Load Terrain and World views dynamicaly Moved them to separate qml files loaded by reqest using Loader. This allows to keep PFD working even if one of views can't be loaded and avoids the cost of loading expensive views like camera. --- .../share/openpilotgcs/pfd/default/Pfd.qml | 43 ++----------------- .../pfd/default/PfdTerrainView.qml | 20 +++++++++ .../openpilotgcs/pfd/default/PfdWorldView.qml | 29 +++++++++++++ 3 files changed, 52 insertions(+), 40 deletions(-) create mode 100644 ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdTerrainView.qml create mode 100644 ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdWorldView.qml diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml index 64df9502d..5b6548d22 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml @@ -1,6 +1,5 @@ import Qt 4.7 import "." -import org.OpenPilot 1.0 Rectangle { color: "#666666" @@ -22,46 +21,10 @@ Rectangle { anchors.centerIn: parent clip: true - OsgEarth { - id: earthView - + Loader { + id: worldLoader anchors.fill: parent - sceneFile: qmlWidget.earthFile - visible: qmlWidget.terrainEnabled - - fieldOfView: 90 - - yaw: AttitudeActual.Yaw - pitch: AttitudeActual.Pitch - roll: AttitudeActual.Roll - - latitude: qmlWidget.actualPositionUsed ? - GPSPosition.Latitude/10000000.0 : qmlWidget.latitude - longitude: qmlWidget.actualPositionUsed ? - GPSPosition.Longitude/10000000.0 : qmlWidget.longitude - altitude: qmlWidget.actualPositionUsed ? - GPSPosition.Altitude : qmlWidget.altitude - } - - Image { - id: world - source: "image://svg/pfd.svg!world" - sourceSize: background.sourceSize - smooth: true - visible: !qmlWidget.terrainEnabled - - transform: [ - Translate { - id: pitchTranslate - x: (world.parent.width - world.width)/2 - y: (world.parent.height - world.height)/2 + AttitudeActual.Pitch*world.parent.height/94 - }, - Rotation { - angle: -AttitudeActual.Roll - origin.x : world.parent.width/2 - origin.y : world.parent.height/2 - } - ] + source: qmlWidget.terrainEnabled ? "PfdTerrainView.qml" : "PfdWorldView.qml" } Image { diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdTerrainView.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdTerrainView.qml new file mode 100644 index 000000000..f56f6d89c --- /dev/null +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdTerrainView.qml @@ -0,0 +1,20 @@ +import Qt 4.7 +import org.OpenPilot 1.0 + +OsgEarth { + id: earthView + + sceneFile: qmlWidget.earthFile + fieldOfView: 90 + + yaw: AttitudeActual.Yaw + pitch: AttitudeActual.Pitch + roll: AttitudeActual.Roll + + latitude: qmlWidget.actualPositionUsed ? + GPSPosition.Latitude/10000000.0 : qmlWidget.latitude + longitude: qmlWidget.actualPositionUsed ? + GPSPosition.Longitude/10000000.0 : qmlWidget.longitude + altitude: qmlWidget.actualPositionUsed ? + GPSPosition.Altitude : qmlWidget.altitude +} diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdWorldView.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdWorldView.qml new file mode 100644 index 000000000..9e4a02b3b --- /dev/null +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdWorldView.qml @@ -0,0 +1,29 @@ +import Qt 4.7 + +Item { + //worldView should fill the source size of svg document + id: worldView + + Image { + id: world + source: "image://svg/pfd.svg!world" + + sourceSize.width: worldView.width + sourceSize.height: worldView.height + + smooth: true + + transform: [ + Translate { + id: pitchTranslate + x: (world.parent.width - world.width)/2 + y: (world.parent.height - world.height)/2 + AttitudeActual.Pitch*world.parent.height/94 + }, + Rotation { + angle: -AttitudeActual.Roll + origin.x : world.parent.width/2 + origin.y : world.parent.height/2 + } + ] + } +} From ce00c0bc4df52cefe839c2e571c2e1f4f9670605 Mon Sep 17 00:00:00 2001 From: Dmytro Poplavskiy Date: Wed, 1 Aug 2012 00:34:25 +1000 Subject: [PATCH 122/543] Fixed compilation with OSG enabled trivial .pro file fix --- .../src/plugins/pfdqml/pfdqml.pro | 21 ++++++++----------- 1 file changed, 9 insertions(+), 12 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro b/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro index 1b2fe8832..e1ba3bbd6 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro @@ -9,11 +9,6 @@ include(../../openpilotgcsplugin.pri) include(../../plugins/coreplugin/coreplugin.pri) include(pfdqml_dependencies.pri) - -contains(DEFINES,USE_OSG){ -LIBS += -losg -losgUtil -losgViewer -losgQt -losgDB -lOpenThreads -losgGA -LIBS += -losgEarth -losgEarthFeatures -losgEarthUtil -} HEADERS += \ pfdqmlplugin.h \ pfdqmlgadget.h \ @@ -21,10 +16,7 @@ HEADERS += \ pfdqmlgadgetfactory.h \ pfdqmlgadgetconfiguration.h \ pfdqmlgadgetoptionspage.h -contains(DEFINES,USE_OSG){ - \ - osgearth.h -} + SOURCES += \ pfdqmlplugin.cpp \ pfdqmlgadget.cpp \ @@ -32,9 +24,14 @@ SOURCES += \ pfdqmlgadgetwidget.cpp \ pfdqmlgadgetconfiguration.cpp \ pfdqmlgadgetoptionspage.cpp -contains(DEFINES,USE_OSG){ - \ - osgearth.cpp + + +contains(DEFINES,USE_OSG) { + LIBS += -losg -losgUtil -losgViewer -losgQt -losgDB -lOpenThreads -losgGA + LIBS += -losgEarth -losgEarthFeatures -losgEarthUtil + + HEADERS += osgearth.h + SOURCES += osgearth.cpp } OTHER_FILES += PfdQml.pluginspec From a140c76a6fb00d91c3537792a9749a86fc38b72c Mon Sep 17 00:00:00 2001 From: Dmytro Poplavskiy Date: Wed, 1 Aug 2012 00:35:21 +1000 Subject: [PATCH 123/543] Hide terrain related options if compiled without OSG --- .../src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp index a47b7acf5..929dce289 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.cpp @@ -62,6 +62,11 @@ QWidget *PfdQmlGadgetOptionsPage::createPage(QWidget *parent) options_page->altitude->setText(QString::number(m_config->altitude())); options_page->useOnlyCache->setChecked(m_config->cacheOnly()); +#ifndef USE_OSG + options_page->showTerrain->setChecked(false); + options_page->showTerrain->setVisible(false); +#endif + return optionsPageWidget; } From a8fd51985a0b2dab395ef620796c0c0730125ae0 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Wed, 1 Aug 2012 02:44:06 +1000 Subject: [PATCH 124/543] Add Steve's system icons for the Welcome Plugin --- .../plugins/welcome/qml/images/system-off.png | Bin 0 -> 6484 bytes .../src/plugins/welcome/qml/images/system-on.png | Bin 0 -> 9983 bytes 2 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/welcome/qml/images/system-off.png create mode 100644 ground/openpilotgcs/src/plugins/welcome/qml/images/system-on.png diff --git a/ground/openpilotgcs/src/plugins/welcome/qml/images/system-off.png b/ground/openpilotgcs/src/plugins/welcome/qml/images/system-off.png new file mode 100644 index 0000000000000000000000000000000000000000..443c99bf1c46a743c729edd8d31402106e92aeba GIT binary patch literal 6484 zcmbVxXIK;6)^_NfAcAxVq4$ImNN5595_<0-kpu`Wlu#l9p@W4gC{jg`Dnt+jK?ucy z6r~Abp(-LpA5n@ZeDR#;Ip6!^T^<3bHs)OH!t4M5fD4U6 zI?z%A?FwUMrri}vtRK@7A)=`p(UIU!jKxIa07h8Cc^n8GiV46u;4oNH#0X9g0AL8j zJGl|vtgR4!giuw?9~srS&~O?W0MIjx3&;2cVsXitRdFn zCb&R6>Ov&W@q&$$--Td5I2LSZ0Md&?&=iE?h!{{@Xh>KTB2FLtFTDs_{!g_U81yd@ zVz55=-%hz%+ks37kvNc+s)mXm1PTSgV5(3}Ef@@{3{re`^c z4=~MIB-S6{fHeEt7OkWY4kQx85o&6&v9YSL8mffI05vEa4*#P=U0sDHp%O(3BVyuI z!lI=9(SXE7`9O|;;^W{14Rp&S{x=^4XO%J z3l06#u762K5gl;<-;Mt&9pyv{$Ei8sq6pEEezgAZm-+`xi{1Zj=#L=H8-#5np4KUt z5G27bIusX1L?iXVv?r=qJQe|g>d>O7tqIXqhro28P#vVPv5}?*Oh+4z)HXJP{-fi+ zVRc|8M(PkPIMT?3hBSp5!!@+wMsN)?Ets)}i8|yTEIKTThzaw<{bLtTv->wz=YPc_ zOd@d@A|cX=KnVGV0d|1|A|Wb}5DqeN)KZ0ltTBH0us=0_I_Tf+MdBjyF*vMQBq0>^ zuLvXX|HT7M4Q+_Fwy~*+Hqyux3WdUrG<1-fnnqesEmI>Ss22EdEcX8rH8q+uYJceQ zKj`vL6^(;`vi~7Jt?-}WgA1dLnMm5;U`V^k0RZr)ppiySaSL1Jmd(zlXEHWLx%Yik zK|s^iDiHmp`U83-(^Y#b?99gZvs2|a#A7a4?KiWCSrcFC?fNbTThRUSX7JeC?x=CyFTH-9p>O$vgeBEf|KPc5)62)b#EmIKz5TaQ{y)EOe7vmI=Zn=8y>{Q1|B;$yDdmgHP)RAF z?{%|B$MfEA&z1a-_O_p->~DVQKRG6cs`HX{#GP1t9v61mklT6ppB5>(h9xYg3ykGU znO~WGYR%$u^Y=Kb%S^2FUpqZtU~;wZJW{8A! zEfZcCp7g>m9#HO?-RE*i_B~uwAwlbGD`DF2<8C*Z=Zcr(wcdxBx_HeF*GK^f8Mtdn z3lF0=*`3zDe*LN@-rPH2xv-ZhkqFs;AK!YoR%q+uDa!38iKz8vsjMfu-R=&0-G(a_ zP51F^)`R5mXhydpCAzrtUl0#_dXjz| ztmf(_cxtW&yNp=G=Tz6&b*jkD)T!WqU5-{VW9ZSoyVAoteaG4}c)MIkLV|#%T(Y}N zT4-19PuPDK`>~~G$M|Z?gR!Up@~qqA%QaRHtm@XUGrK&ZjLWI@4A#p~#x$dZ_JA7h;BP(#~^V zFg@&IZz>?KukRX{ubDNPrZBxiM>nPdNKNFTIVgK>0k8t<1D<7R&4+FMI^6xZ`@%35 zgRm^(DoKjWCM(o5p4w`aSK!b!Kz{RTi2Lo)XzrC)wMirD7>!e+OgV`47Vn<1jya!T zmlm&$U!t2;4?*3GqY|XG{H84DrWAgGdTtsKEnOO4xAflTC+}@PSVT}izNq}N5<~tv z@0aUMmqJmJ-Y)hGgFbkFp{WGwm*M`9sBoxKXJ+{OyCaM2$g)e@Irj4dFvA}yt^nihtu5k`q&^E!oY-$-2Dl0r!*1tmp1rNoFIf(7 zZg48YvL`R^t~0t^TTm9&JBdGcuCn|1=VtlOp)g4}Q3uOlx6`%CEzooHv6N7zDTxyk z6Z5Ch&c-`vNmazZC*kvqLOXt1w$8Ze-l|#CuwLh;Ea^CweDXG3}3Dv-^p;*52<27hjmh^JgyIMQE0;TU*uHb{vi@Lc1~C#}GXXRk zbJ{Ph(S6=|*E9Zme=*5fv^WzdQK@d{!PcB{>deU?m?Ry0UG3aXpI^Hs4+bzoz@$e( zj94fbO4sSFRoywnh41wkS!#(!fM{0-b3xLnAdS!3C2Z-48v0_O6`!4bdNv#-fn}li z)>?TzZW;71Vae70M7QQoJe-``*j$^X*2kz$RlkcZmV6mbuW@n~fQA*%;-0xEX`-({={ zp~eoF&$6#)uJMR)Nm<NE&-R@Bw_VaJzrQg(1iO;?_JgAf5sz#~y7z=$SAU{^XQh ze{d|E?)HK9ehRcH(^&?ryJfL#!_}~9IZsNiUooC1RikoIvY&S+biWXpi%zsr)r8smARbjfVlVmQG9vp!Alchx3A_pqnGsiez`V&<#}I#m|^1E@^d?4cr*G*`pAAv z2^%vf2C=};WN|A^h7EnoFP~YOiEX+OYIPN#&BSAN;%KY?!AYpRw)I8CeG>$LSA=Pv zHfiK~{z}0@P=bs<`@-J~S&_}RzE7G#o+mpO@eV6XIa|VeO%oTdlyu0azbxAgOw!s;ufbsZqhsUceC~7_My~ zOTAUl0k4lC^c`khNX*BE^bNbMF3h!+b71mABf5T5T)d3v4GxwVwL%*1Xqf=h%^ z{=im`6DYz2K9&Gx4ZDo8BSWR44+;QApR*=vEjqo`_sC|tXQ?>1o|wCS!>GcVJJrlW zM9QPLUZ6yQ?YD~*E5Mq#UGi3d9XgRB98NDD zn!U7y0Pv-9XZuMs77Pq_$c#UJWOPUV22%*p5$RSiFV!jZS`XA|`j)xBP!o??L$ zdHq*^5966N0p>CTvY4XCi?=yc>05ZIf0f9EcbmImOLHDS_47c`VOZ1GcB*TDrREj6 zt0SUc#bTcPb#p9>{YeZJf;VTT|4K;$ur^r@ffe%Dn7PZxq7~9+zbEg9hjQuPw?+%Kg>z{q0zgS$PZ~i);7`1E+kal}CX*YbEwMUG5C`1f(E`(KwNk zaGp>|?j$T42o#(Ajttw9pEHR9=_B!iJV1kks^G$F--&H<0fhX{@S%WSI?Og zCL3h&ORA=AL6dnQTzPJ>KdIj{EoD2unduEmYMoK=tKrJ`*`R5;N^S&lAGe$ky>pRKQ)*NrlZ~kU#sj)TfX= z$@IK4iaT^cwzA^RQDt;L-^DIQ^Im7xc{JV*1z>}2NoY-_$AkSXt16DZ4P~OKjqt(> z8NH0(#y}!ns>B-le zuV#OYJNdmoe%e;=6#TBqLfG4`$&TcN=Wsz}+egS<##b_WPoPA;Daq**Mx-=wW7)dp zAZ|V*NSe&D?iK>t{!wPjCU`re2~8))yg{D9UY+&Xk&kb!xBX>RA|mYERrh0a?wtSd z)Zv&YRppyN!N;K8#)ffepweYZ3V+(muE`?Y%4P z45n{xdSo*&d5$IArf;$ao#8zrgSIwxD+t?tSudJYk?9f*s5Os&Ma)6keDkJ93x`slMgj?U}`4)l7J?CV#}+QB1jRxJuMvWoevECazaz+qDq>ljbQ z#u3t;!^pploAg?bnQz~F)1pp!^kbxRse33ZkUQbYsi&By+QVW?7j(Y=l0~}+ifwTg zpOI~dU`on+J&iVTMpsz60C6KPSEHVbK-zrzZxzUas34pvPd;#q)z=~0Zz{)z-mZp4 zf%ogzH#b~`z*28n!`)W92orRn zOd`_&EoZ8NJcLTGFDP4VgSqBSUVTH$D>i-=InF5`YzK%ooVksy0Ax=83U-mP@O0IM;Adai{#f)Qhpu&*~v< zp(?)o2)YIz-}DZt)a1L@nA9SK;;Xf5qV0kiOC*iwZP=}N6?1i|oyvmzx&rHsJUN95 zdG0cIC717ANd92SKCN0!{{RE92x9ZiqCUHvkjC`flL;3TFI<^JW)RxH|7G1~R6WYM z^hZctf@xX&ufh8^?PI9IIsKrog?CD;Q|PUXQ|>=AjQ=Q;(4fA7_xWH?SXz@1$K>Pv zn`F>$W*l@RhO_7fs;%5D%K4kU%D$VWey|k%Y;y+o=Xo#^N0i0Tx%==Db&DZ*>=guPme-bruUc;o^D zD@V)T&nCUIWA8qG;41FFs-L{F>Nw(&2?2ay(nTpqR~J7n!oOg{7=5mGf#B%wg_pWA zx?vXS^4tTjgcS1}!E#?ut}&CCNo>IOS?oh!VIDdFB&%$xf8_E=iPx3>Pb>|1OW&KY zZx8O0EWMQDOd0G(MTqI|cY_iyG4m|ls5Unr-K3zP`Eyd%4CJvUE8|E&viqBP2#F(& zakAve(}c4&!#nKZ_b1^!z0}5$7fsh^WDZsPgaFSy>Fu3~kP;R)d$##+vCC;szAoQz zb-%g=&`c&Az6m}N*O4gUD)D?ScMHMg_1>4?%G}8L_5s)9QD%O&X+~8OBxJ@i)YpNk=pARP-N|exv4N#^taui)txH# zFd7*=Sn!omb)$-9?y{97_E-O7cU4MCDqdz(w3B?B%O&CR7`dHVPTT%*AdqL%$l40j zd%Luy{z;MHeO6DS1=Sy}*U16tpPhSxt-`04*lzlrxj%60)~)L(gH;>u*x zbLSShC3-J8lx|^V$Dh#_j>mX!rsM6H({kDIuVZ`G)FJ{6(lQY`ItRcWf;=_AD(!A_ zt!lld;KT6c!BJ7x&olnN_wy=mUoGt4O^)Z}1x~%p?FN*H~fwqbB;1kpSwu2R4x-G~1uuu%~d-$_1PPFmr#P7WA7WuRP=fRSg{o6n;Zy}~ZtP7(=3TR#vyGPz`gY9&^(-$Ob z2?DhFX6)@NYXN`;VXBa1heo}ak>}l*+D=RQ-fNd(4Q^{FyG-NH6lU(yx*@+>-@2sa zzn0d9PEk7sM!72%pBf7?4P!d)mfX>GNfn5ugGZQ$tJAeqv)YLC5~+s(n>av@f`Z7d z`yEusW8M5d>a}&VE6im4(t^YF%J0_lf$VCr5< z8YW)WCj6${EnnjP8_WH_ zVnO0gFk=^cCk=ahoBw2hiiN$4y|abA1C_WsHvmYbXl!C>_fOA16ZBu>m4G=}y1`7P zoa}9>{-rR;@_%5!#mURg%PS@+&MP4*2?PT9MLGE-xVS{Qf!va!qCjrye`8Jme^g_8 zA;b1hdi+1>@}I7k9Q>#H-^u^d`0wQdvwK-HPA`jtRkGI_0fB~9Rzg(6W9i7((t&(F zd(Hk0RzNp5f|)}w-)p=!*?4M6IS#tfDLI%ex&8Nfy;i`9-L`xJTc$=~f^w-wf*ez_ zla`t~!m8h{)JW5kUjE(#*v4L33tnzPZ0=QHnga1QSZ=L&M%X4%h* zLA%Q~zm-S76aVKmYk6g5oT8#4mW73i3UG~g;ev*wuVHDi&4F73?;k~?7`oXUIbHLr z%F(L&63{YrKv4ipn@~?(eHx;vIeS4A+25-d2OH&a*bW~08}FKz6-R67g@o69%ke3#^;WSJfLeUK;fU`-e6 z;sizoWubv=JziX_%G~h5-~P>QZ4dnSjOqQf>HYNC?GkG0IT=ewI_o8TAQ0%OuBPUE zt@G}Of7Hp-S#HnDD)NaJ`PsM2ZPyz8vR=~-6@Z~pO622kB|cwvg}by)CUB>oDl!(e zd^RXF1A}XB!SQUF{#NAq&>sTzIjWkQn|sn@Aka0{#M42zC{aNHpp!CdW@l$Vw^aF` z=01fzpTC38xo>pq;~vJ(q++F11jc$O9Z}^SVstTGH&*n>6P>C*vswq!jb_{=YX*Pf z|A_0YYh7Jj{M!G9SENVT|3RGnwBygk9iZ0gjO9zI&Bpp7YD78hI&uHwg+Z_P^Q`|< z-%xvyL%kl~&QWt@thd-Ird^1g0S-kp=&L7b=Q&fxh&A<{Qt;YcP{ z2)02{zq^`Oj^FA1TJk@A?|&-3tP7{YQ+^IcEyryWgPS&=dYT4GW}wNV^RdD?L`IrL zMdty3do2D?e)6uxH=%L24(eX_Os?sPG!UQDMO+ z>1aNrm30+t4@<1e6zOxDa33^^cID!$OGYI{;txQA{B(xpyyNicco zCef+2qrs9tbV^up$mxXK{7eZit@~V-vQpv(TB|52xosRa<%m!AZa`|VtX+)p^tz_G z9t)r=+o9`9sLwS~hgiNzp+`&^aCW?V*MAyFb6QoI1F5(OX3>&uU6(C|WGH27>@U4Y ziOt&a3Y;IWi3YAYjoTir5(~KO9Wh5m-{E63DNK$6}D4wkF(o ze{NDlgenNkDdq^s#iqC8s~eBfps)2*D{3q(CbmMK zs|D~+tHRED%Iy>XKA3h-)on*q&qH@UIl@hKjEsjPY6Jn6^D&B6fsLN@$D7LpX2k=O zhou9Ph&bbGd^ouxpQk%7yaloHJB&ct5|SYlY~*``XTbuhdU}z&*C#>t+yS$na69?k zF*^!%Jak(dh%4|SMn85l&2V8ev5@i+A}TYDvX#unTQiSh)xDlsG`U?RL$CJ!nwU=Q zR@cb&JNt(11L>RmmLi^$ev|lD2iE2AuvxnGgTuq&-hhk@QkOcq4Rf1I|EC8Q(oDT{ zMJwLzVTL~>i{xO>2^BPOe#eLHFT=PV339)dvy9l&qfE92c5mC~W7bg$sEVhDyGtr7 zLkE9%FU(Mn8$1wuzsU`1&qq1~6AVir;osP=Z*}`|&6pp6WK=g8k+l~7xX~uyC6sar zGys{B<%WpxuQNsAE~Va>U3k9|VT&x=!+M+VE&<~v%Kid|d|W80qamT8Xm3ygRWvn2 z?6W{o4z%OogIB)>f2!zVo7W?=QIPbN_6qPj5E2q137|_2n4cZYE7N3*hw6+4z`n?# zx~|mas|tguZxfPc`LKiOhl{$W&M~#LG)-(j1WCwA85mHYi?>q{A4{u?V-uzL$P^}& zRF#Uc#0Rxj#{?_bBrFty0Mb-dVbt)s#K*+dBrULvVkUyTMR5T4=zt&#b^i!iQ4r!O z{KEy$VISRT5t6ZfyFg$^4uB_uR>>6u*JXKe70F#48JVqr0+y7D6-m3kXU|CXP2<>L zg5h%W&Y90;lTd3SWu8$D^ux3)xidKAk=ZDOZKq=ju{`Q}3tGcxy(?Rz+8|2-OK$9A zlbNZdjM!LeALMg&Ve@LGc*x2?#rxDJHj7Yt11)vYSSO>$VfW1F>p7y$&;zBN84gz} zb4t=jp}SXht#lyEE3^vvY;vLhj1#p%sOTBzMoNhxQ$%Mu>&U_+MYX3>#(e_$yGP#Bu%E*9VpN*g#5MTEy&qbbje-cpe31 z9hYuA27h|dVMzJ#BV8aJRuU9q$tbs2rp6P}lQhQsE4(Bg&ttcZ?k&NLFc6;u@(QcMereAqWdXkjccZVz&FVoEr6+GasUak4 zT0C8N6WewECN_z#Et(vE-bM9OmsC`Yk8opZZ=~*gthWD(TqP(n=2yPOqV}!DsY`vq zHnaG(kw6E|;Pnj+0S4z!CVsslr!>okclIKoYmGyHL<=~Iy0m8hSWwt2OuET4$dOKb zOb1SdE3nqsjD)xD+!)(E@Khwbf{iZn+;@c)Vpb%z%Q5ZS?*w(174@BIQy7EdMtc&z zEw6o3)hcJutcp`p*ZaNY1n;O!$yHAx2l?G!8b7SlcZz10lW0XIi#SJAA8&_{9P`dD zk!GeN%`SB>Rg*O=$^{nU_!zh5OJxoVCXT@shvDVnpbvy;-6w5LIIi5YO^*;XOU8gl z@oYX<3tZooKg%67BkCYcl+)`y+BRlu@aY{;xH%wZ?qkLGu;#GB&Q?O!AAmPzcC;At z(_dBUz^>?*)z&y~T#duAOT1DuJ24S?7odZfRXIb*x{HA2oSwZNa$SKISCA_wgs?#s z;`hq-3{s(EJN?CoJzHtxELiXM=_IFb@{t5*WFH^B8s0Wy%X6-b*B|dozhte^R*v}a z_xEU%lR3GlS?d+npT3p&L2xS5na2_0xB-c%yEmtyFepmAx7`AEu2@bnNu-W}sBW~| zHyeMy;0%AwXeRX;Sr}~@Xy-n4QKtBAY1L~ngiORMSJi^7qHhO#!KSc_=|Gwl%?Chi zEoMCIQFC?F9Gw{!bZFts3pp7-&caCm1z%g%G=g_aOT`StqPU-q#`qsn5M2(Er(dDr zD{R*pzgK53c{=TuT3D#hgCO`n9-}V%@rzc64AJ zHu1ji>OQf_AiPGYYprk3F zCwQiqg$nc^hvHBU*0>{fKI~x_int==8u$kE%U~$+KsKvQ4f~!W@3rBLt*<-kan0Uo zJ3iD;gLCx66IK!f8cdTZ;$dZ_$&X^HY>AIc4z zvhiB+0Nrz019(dOV!^t8o~kN%lNT%j-&+fnd$nPXJhM$B1^p_SKViBKIUY=>y)%IT3Eui9h1BMO5sUs z3zUYY=q+?QvLSlBL_^|b4t=|O!V2s79r85gUpV z((a4rPN}f5F+)vysK2ndGUiWzK+E)@tiUTj{Ojtpy~f(g^3c)zBcCr!t_W_fKHCnIl?Lr;vvaaOS;{efbaRn-_GH4-e=RzRJpHR5Pa}KkgmR(K>!r z98(C=Ai!3SG>FKcoK+_PF1=sT{=v10GXHr$s|Qf(Tc}v(9)ZYLTNgSwYD|g8iJ}$n zm-2(Zh)#1#UKm{X5Oj$*2@WDzHePjv5@fAb7p5-;@i60TP?1#v53J-qZdzDWZc<3o z7}*#h#*O2{m$!xn(Bu(|P`@Hk*GmUXcBwEVjx$SA5Pm=qioQz2sX_eF9~2)@u}3{R zL7Di&1N^PcBgc^*aCXN~+ZvR|aKcyl@Jg3qxOd<$X{F2paeam(_oPgYf#GPi5UZ`$ z%09*~z&pP0*AkF^q2%EZ%^4myDtH@&l%-mvsay?Ns5~b=$KKxZ7ZV1V#xL%fJfInt zx*MnDfTRd*G6e-?(?Qme;`W0ZtQ&2lRokovRk{3&&gr-`uM^9d3<|WiD?F2^pK79Ibt5j8^*^DKgd*8<91Q}S`XQKct=+ayP8i!mnN-swd;xy2EY+x@$t zZ(}6RR-1oW93GpyGGk;n9i$NzY&Gvom%yahNqVpq?V^+>eqRU6k}t2MCi)g4Bt+5? zCV%A-T2J~No(>b#kEu4d4sf@tu~2E$_{5`ppJJLAv#d9LX za^P*|GI2kc>RQ+#W24-3TfHO0F?Q#Hh75;|Qy?!VR?)tV4-!ivJZIY&QV}4vVs`Yj zA;gaUA!xt7F@qQCwG?3$uS=!Y^3b~v8{@p=KQZ`yGPhGHEx`O}K>0D%+L@z1%||_$ z5BOU$xi;sf->eJoUWX^qCG*6164S&+P~XBAyVYCotf#v>tGjH=>>yB@O;7uai4P7x zvE%?ZhtrJoUvmH;fxNhbTMvRuf8C%kzrf*9su-*~2c6LSadtsKruPAKzC$2TV?mBD}n3t75)6#Az z_k|A$bP{?T;gysSb$>d7((?BPVrjPgnb-VxTEOkr5)EM9-KAm2$*~S2JWw6|{_O6@ z>vOQpw^?T>gNaw#{)~vu$Q{L1*A!_zH}@5vw8cXinc73XQ_$)4$p?&R{ly>ADH=C`uz0Bn-kV+w|%Z>X}$PfN-$na(Iz=sc_&Gc ziKRx8iN7=-f>Moc|7W55voCIUJ>e1YQZ!s-NJn4XS)gr$&+lx5@VLqMZoxrx%V6bB zKKA_wJl(-S!*}R%E==m^2~M;voipAX=*J3`UkhvVJRBASv}D$!l?Yy3WNq<=Ik+~4go5V}g8~M}e)8jqWEa5Ks{YlPZb`=)vS-b0Q>~s*b z;m9=(Ch|SEf`ZxamY7TcP)4~sbnQt$B^9Y*(?YBKRCnN}w-ok~W<{afv*PT{&eTOs zc^VWt7dg)39(bOQrZOC>x?{u;@xy)9$@!Ev`b)Im(5s#qWaQT}TC4koDQOHvlJOjB z7A|wG8Szk?IH^Ls%E`+JQ=>RgpcH5^rjSd{QF)*-1j|pB36q6Y&cG0Ro0`xosTiT; zNx%poFPVzPxaZD!Tur_`{Lu-gUJ!+}OC7@}c{-*HLvNhE6fJh@s?6%(T&iLU(JXtE zWFlOi+i6sGbo2yrqD#B$Fpu>Ps&;h=g6&qZeioRJ;Pd&r#t#UB zl^OX*H8X~+crM*|zBy*KgB5hBhDMj{w};-NhdjOx(gPxUCm4# z6N#O8B!9mCc3h!9m}4cb=lb}%F*gH41o>yQoYy7~fx~VlC*+`P)7krqJ(h%eUfx@M*ga$SKyjZ z>n{j(0$FKSlJOZv{g3Ic3xy0;dSO2o)PB$hIsA&)p@{-)?%d)PQ=_(ZDDh5|YmA|` z^O1+RUSG919&Y$p!sQf*>9jhFCy*P<0jWtEQMMfyPm)oBS;O`G+$SMN4rdZD*#u+L z^xr$#6FWy2q>9ClfW}M;o5W zBS-?edh*W5hTeX-Cq_*Zgw!;UaD4hdgl<{FQ-j5+sy&q)kh*}#K0J?;WmYgbH~40p zSpQR-L)`A$7$uj^FJraBd5m3>OPsiVYVE9*E4c&A6Z2dBOLh6H1hIOjXngnIUWL#C zeiU*hM?b`&EI)O-Wi70YUPuh$UqTUqnigs*lUv2Tu&*dpRNl=};#t4ubiKz=GM# zq@z8k+;D5Ifw@9YM(0B2KB1Rn2&2G{HWr*nMtD?HhTH_&tSOyX=HUjP6ea8Wp0IgN z0hn3z%hpW!;0>gyiqO0&YGbuv8;j7aw*HodR!<7C26)#{+)2nrd1PEs6CW(4Q9O1$ z%ZX}Hv#UE3p@K_6o!79iE*Koyc&EYb`^)x+G~6*Kt*SCQ%vLW|baU zE}@Kvqyt!O(ih=b)y)to+m`m=mD@${cOj^Aqlo3Wg6i=u<&yq#&XcH%Ike!Rd4#YQ z&RW;LVM?#AQgI#^>}oYfBDO~<2%{lE0UF=)&Wgi(Lq9uuVbFUqhPs@phcqO4Tp)Yv zYSCv_hs_=?Fe>voAzb4$X05&;eIk~oq3D~~7s!5y?F>~$I0o^V-qT&~10b;wPq@P& zk*z_65=>fy_tBK{IqN79p?u~%oUZN2w9dU@=Jza3yMFxF{BL4ujG2g~3;d)q&zloZ zZ+)yq^;`T>$qrDJ0uvzNPUADsQVGu#MSjOd43@JrP)U1piaQ=7UY+))>2{FTn}GhM zyj>92a;#o~x(`4K2=B93+OsTTZ@*snnAKF+_Aa#3mdb}XVp+bt8w@a-W^nL&ExxUi zu0?TnQi}S%;(EkKTraV#4*OEfpgYQ ZSAF+K;no;hv0Sde?kVf`()WofWxzAfR z3Rg=dmv2tyHbk|fel8xQ4jxU7R7^&1k_|c@abwL>eopUq57YFvQ299=g8(bpl3e6! zKP1@#3SWVd6i3V!i)?y{U-?*K#`tOHcZD-3W);a&wx$9OASKZi~tF z|GYeN_4%_0X!9_Am-}9I>?hF;K|bidpCaq-lF6r=pz-&X3tn+-w9~ePLJ!^g(_yTC zu!mrvg+rkNywBOpH&gCQT~w7D@hk`CFV3AlMc_dJ{loSmSzE6ms6_ys3enx9C)R=C z^Qo?xX6KbAv-0Bo>|!QX-v^(Y@9*SVnk}9?pRZZQecXcS@dxu&Q63{@=zl+a5WZy@ z;-Be!sI_;DPCa1mQf=w*-C+G9sZfbURbTcRO_MiC3^5?BE(bdsL@CyN6%dWv+4Q%c-P~m2l+FU@$>G< zJ0D{ZydeUI1bnF)EAIWbx~Fb577%@w40yoAXE=4VM+C#HG9`&(nb9kPPPmh9((At^ zZS4oYvx~}~(wWduMTf>CY~}^*bbYmkRx>=OApa<#ODP_I)~KCq#WBC7cFs%YH%KQu zty=HdCTrs7K#cs3r#k1xwN6Orr-;x9oi;SdU}Jzx#&RZeH00ufy_EDvhGL|s2e39P zq(eSw7oS*?EQecIn5dE=qHM?E1(yn9!?9`=Bjeg(L@bZW!6|2oZHjlO7blFB$0{t6 z%39y`X{{N^mC0CoG2{oDbni;=iY^>OjdMZ2s>r8%f)mM?W(M!R62JjI@CN=tLuYwG9 z8d5WH(v(bQPX^JAqE0P>ES@Kys-B<7#blWis#R9&4_qg6LKL-)1M}fY3NehqH4&&E zTp3DzIw5&C)J+`&or9-mg{rpk_T^@-NDrJ26X!*Tl!==17nzSvsX%x{ZToi=dDH$a zXu-?IzM#B~!y$umgCG!&(anjLLgXRU<%P#H$B9Wf&!b5qZv+6FWj7faz_HYFvUr&# z=N|X$?;w^TVlF!CMGrwnE8oABs^GC;b9YdAG-1!F7YXVBa4L{a$AaiY2s_uc$pvNS zspd4H4c%TT3^*V0VLa$_sry!c(VK?d@`|^_PI+*&K2ZLGB-iTf1>=>C*I;%rUc`FR z`Z8l}+QJ)x2F@K+w0IN#Knb<-Ym&-#-jCFS8(vk|e&q?FuspPU;?L&hj%Q3N{yOZJ z`k)3H?i%%*F(#`p54zkUFjDrGM9s0$L`)qIx*;y*GvYCN48dld_*;AA_$;SNQQJCQ z&D{sBRz;;}(&Bcg__ld=i^@;AZVlSi0{^(@!gwK_u`Y`hrh!tr_t%DjAY%lYtksoB zu)gNoXpA2=L)Zn_9WO)bBSBc)*;m;RiM*RB3jfun;oT$08=WQYTq zZM+kwuHBd4Nh$wHS&B+pYvanxzYsO2hi9MmI~%c)uI^t;>b*x?)%R-Q#K`RJE2+w< zTX9MpsB~{bxZ46`Xdl){2&HOoX$hgVWu*YU5-~2^S8XQI-#KR51t|i+3|qD-cUv(1 zjJFCX!+Ri`4gS8KKzHKV$Am|MQD}irCbwcOS4o_xxn`;<2Z>U#`aDxyMcs!*X=Z{# z=khgOr!~!$)rKytuVW!D34uhg&v>Ea2BMP7VPM)@=K)mz9;T35x-ul7rS@=}DUpnK z!$O)H=g3IKV4|)QsKB3rt}MPr3y540L~^QS!_wT^ZfjS-HuMdWjORngfVO@&tFqS) zVfV;u88aD=#5BBB&NShksoHVHznwmN1!4l2ttq-1;-_FIo*mik3i93U!%h)|TR` zP!pk0qe8=gwmx%oYI-`jw3M;%H>Ls_A=rw?l28Gwq;hR_Og*>do93q?&7>49#KEfP cXCy2Hkvt4b4@2$ne~zTdN-9ZIia~<@4{H_k2LJ#7 literal 0 HcmV?d00001 From 67ba889659296c43754ea97aa79c33328d39c0bb Mon Sep 17 00:00:00 2001 From: David Ankers Date: Wed, 1 Aug 2012 02:45:15 +1000 Subject: [PATCH 125/543] Swap icons for firmware and system tabs, matches Steve's icons better and makes more sense --- ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml index 801aad89b..d17ec963f 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml @@ -2701,10 +2701,10 @@ :\core\images\ah.png :/core/images/openpilot_logo_64.png :/core/images/config.png - :/core/images/cpu.png + :/core/images/cog.png :/core/images/scopes.png :/core/images/joystick.png - :/core/images/cog.png + :/core/images/cpu.png :/core/images/openpilot_logo_64.png :/core/images/openpilot_logo_64.png :/core/images/openpilot_logo_64.png From 5da204f4b793e14f670030067db9f38ba9115a07 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Wed, 1 Aug 2012 02:51:34 +1000 Subject: [PATCH 126/543] Change welcome plugin to use Steve's system icons --- ground/openpilotgcs/src/plugins/welcome/qml/main.qml | 4 ++-- ground/openpilotgcs/src/plugins/welcome/welcome.qrc | 2 ++ 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/welcome/qml/main.qml b/ground/openpilotgcs/src/plugins/welcome/qml/main.qml index fea4b253b..4db07bd8e 100644 --- a/ground/openpilotgcs/src/plugins/welcome/qml/main.qml +++ b/ground/openpilotgcs/src/plugins/welcome/qml/main.qml @@ -61,8 +61,8 @@ Rectangle { } WelcomePageButton { - baseIconName: "planner" - label: "Flight Planner" + baseIconName: "system" + label: "System" onClicked: welcomePlugin.openPage("System") } diff --git a/ground/openpilotgcs/src/plugins/welcome/welcome.qrc b/ground/openpilotgcs/src/plugins/welcome/welcome.qrc index fdcef517a..0f1903a2b 100644 --- a/ground/openpilotgcs/src/plugins/welcome/welcome.qrc +++ b/ground/openpilotgcs/src/plugins/welcome/welcome.qrc @@ -22,5 +22,7 @@ qml/images/planner-off.png qml/images/scopes-on.png qml/images/scopes-off.png + qml/images/system-on.png + qml/images/system-off.png From 4c3c94eba5c4a7528ba545133e41631ca1f42b98 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Tue, 31 Jul 2012 16:15:58 -0700 Subject: [PATCH 127/543] SvgImageProvider signature correction to use utils_global macro QTCREATOR_UTILS_EXPORT --- ground/openpilotgcs/src/libs/utils/svgimageprovider.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/utils/svgimageprovider.h b/ground/openpilotgcs/src/libs/utils/svgimageprovider.h index 8b11e512f..a96f2d395 100644 --- a/ground/openpilotgcs/src/libs/utils/svgimageprovider.h +++ b/ground/openpilotgcs/src/libs/utils/svgimageprovider.h @@ -33,7 +33,9 @@ #include #include -class Q_DECL_EXPORT SvgImageProvider : public QObject, public QDeclarativeImageProvider +#include "utils_global.h" + +class QTCREATOR_UTILS_EXPORT SvgImageProvider : public QObject, public QDeclarativeImageProvider { Q_OBJECT public: From 84c7325eb9c9441466e71eb863dd037f7dc0e1b0 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Tue, 31 Jul 2012 16:15:58 -0700 Subject: [PATCH 128/543] SvgImageProvider signature correction to use utils_global macro QTCREATOR_UTILS_EXPORT --- ground/openpilotgcs/src/libs/utils/svgimageprovider.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/utils/svgimageprovider.h b/ground/openpilotgcs/src/libs/utils/svgimageprovider.h index 8b11e512f..a96f2d395 100644 --- a/ground/openpilotgcs/src/libs/utils/svgimageprovider.h +++ b/ground/openpilotgcs/src/libs/utils/svgimageprovider.h @@ -33,7 +33,9 @@ #include #include -class Q_DECL_EXPORT SvgImageProvider : public QObject, public QDeclarativeImageProvider +#include "utils_global.h" + +class QTCREATOR_UTILS_EXPORT SvgImageProvider : public QObject, public QDeclarativeImageProvider { Q_OBJECT public: From faee5780105e69c6ccea8e5c41b02a7fc5f29697 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 1 Aug 2012 09:47:11 +0100 Subject: [PATCH 129/543] GCS- Fixes from Dmytro to new PFD qml file. --- .../share/openpilotgcs/pfd/default/Pfd.qml | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml index 5b6548d22..b25596def 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml @@ -32,9 +32,13 @@ Rectangle { source: "image://svg/pfd.svg!rollscale" sourceSize: background.sourceSize smooth: true - - transformOrigin: Item.Center - rotation: -AttitudeActual.Roll + anchors.centerIn: parent + //rotate it around the center of scene + transform: Rotation { + angle: -AttitudeActual.Roll + origin.x : sceneItem.width/2 - x + origin.y : sceneItem.height/2 - y + } } Image { From af98f4c2a64322308f23f1affa1c46847614a85b Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 1 Aug 2012 10:12:52 +0100 Subject: [PATCH 130/543] GCS- Fixed board rotation being overwriten when calibrating. --- .../openpilotgcs/src/plugins/config/configccattitudewidget.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp index e24ea74eb..fd0f18bf3 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp @@ -135,7 +135,8 @@ void ConfigCCAttitudeWidget::timeout() { void ConfigCCAttitudeWidget::startAccelCalibration() { QMutexLocker locker(&startStop); - + //need to apply so board rotation values don't get overwriten when calibrating + apply(); updates = 0; x_accum.clear(); y_accum.clear(); From 44b13a19ee144b45d5179a340603fe5068a54b65 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Wed, 1 Aug 2012 20:59:44 +1000 Subject: [PATCH 131/543] Move to the QML PFD by default! Yay --- ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml index d17ec963f..a1f331acf 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml @@ -2453,9 +2453,9 @@ splitter - PFDGadget + PfdQmlGadget - raw + NoTerrain uavGadget From 599d46b8fa3fe2ac513c111e21ec6f4afa349a3e Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 1 Aug 2012 14:41:00 +0100 Subject: [PATCH 132/543] GCS - Fixed nasty memory leak --- ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp index c412a475c..19d568702 100644 --- a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp +++ b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp @@ -79,7 +79,9 @@ void MyTabbedStackWidget::insertTab(const int index, QWidget *tab, const QIcon & void MyTabbedStackWidget::removeTab(int index) { - m_stackWidget->removeWidget(m_stackWidget->widget(index)); + QWidget * wid=m_stackWidget->widget(index); + m_stackWidget->removeWidget(wid); + delete wid; QListWidgetItem *item = m_listWidget->item(index); m_listWidget->removeItemWidget(item); delete item; From 0553534318ab3f3498e7d00f216709525e114f94 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 1 Aug 2012 14:42:21 +0100 Subject: [PATCH 133/543] GCS - Fixed dynamic loaded widgets (according to board type) not alerting for unsaved changes --- .../src/plugins/config/configccattitudewidget.cpp | 2 ++ .../src/plugins/uavobjectwidgetutils/configtaskwidget.cpp | 5 +++++ .../src/plugins/uavobjectwidgetutils/configtaskwidget.h | 1 + 3 files changed, 8 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp index fd0f18bf3..dc04a3db0 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp @@ -43,6 +43,7 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) : ui(new Ui_ccattitude) { ui->setupUi(this); + forceConnectedState(); //dynamic widgets don't recieve the connected signal connect(ui->zeroBias,SIGNAL(clicked()),this,SLOT(startAccelCalibration())); ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); @@ -113,6 +114,7 @@ void ConfigCCAttitudeWidget::accelsUpdated(UAVObject * obj) { attitudeSettingsData.GyroBias[2] = -z_gyro_bias; attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE; AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData); + this->setDirty(true); } else { // Possible to get here if weird threading stuff happens. Just ignore updates. qDebug("Unexpected accel update received."); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 760ddae70..5fc350925 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -224,6 +224,11 @@ void ConfigTaskWidget::onAutopilotDisconnect() invalidateObjects(); } +void ConfigTaskWidget::forceConnectedState() +{ + isConnected=true; +} + void ConfigTaskWidget::onAutopilotConnect() { invalidateObjects(); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index 825f9d007..3141b361b 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -130,6 +130,7 @@ public: void setOutOfLimitsStyle(QString style){outOfLimitsStyle=style;} void addHelpButton(QPushButton * button,QString url); void forceShadowUpdates(); + void forceConnectedState(); public slots: void onAutopilotDisconnect(); void onAutopilotConnect(); From 8c69fff234badbcf584e386abdb1d7934fd7d58f Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 1 Aug 2012 15:17:05 +0100 Subject: [PATCH 134/543] GCS - More fixes to the dirty status of the config widgets --- ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp | 1 + ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp | 2 ++ .../src/plugins/uavobjectwidgetutils/configtaskwidget.cpp | 1 + 3 files changed, 4 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp index 9011b07b4..8da07a325 100644 --- a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp @@ -86,6 +86,7 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent) enableControls(false); populateWidgets(); refreshWidgetsValues(); + forceConnectedState(); } ConfigCCHWWidget::~ConfigCCHWWidget() diff --git a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp index 621577b20..91ecfdb2e 100644 --- a/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtxpidwidget.cpp @@ -71,6 +71,8 @@ ConfigTxPIDWidget::ConfigTxPIDWidget(QWidget *parent) : ConfigTaskWidget(parent) addUAVObjectToWidgetRelation("TxPIDSettings", "UpdateMode", m_txpid->UpdateMode); + addWidget(m_txpid->TxPIDEnable); + enableControls(false); populateWidgets(); refreshWidgetsValues(); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 5fc350925..d1a08aded 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -227,6 +227,7 @@ void ConfigTaskWidget::onAutopilotDisconnect() void ConfigTaskWidget::forceConnectedState() { isConnected=true; + setDirty(false); } void ConfigTaskWidget::onAutopilotConnect() From c4d11c40bd17c3c8d6df7afe7381fa79611797ad Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 1 Aug 2012 17:50:48 +0100 Subject: [PATCH 135/543] GCS-Fixes some value not being reloaded when reload button is pressed on stab screen. --- .../src/plugins/config/stabilization.ui | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 4fe78abea..8077fa1d7 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -13911,7 +13911,7 @@ value as the Kp. element:ILimit haslimits:no scale:1 - buttongroup:4,20 + buttongroup:4,10 @@ -13958,7 +13958,7 @@ value as the Kp. element:ILimit haslimits:no scale:1 - buttongroup:4,20 + buttongroup:4,10 @@ -14008,7 +14008,7 @@ value as the Kp. element:ILimit haslimits:no scale:1 - buttongroup:4,20 + buttongroup:4,10 @@ -17183,7 +17183,7 @@ border-radius: 5; element:ILimit haslimits:no scale:1 - buttongroup:5,20 + buttongroup:5,10 @@ -17227,7 +17227,7 @@ border-radius: 5; element:ILimit haslimits:no scale:1 - buttongroup:5,20 + buttongroup:5,10 @@ -17274,7 +17274,7 @@ border-radius: 5; element:ILimit haslimits:no scale:1 - buttongroup:5,20 + buttongroup:5,10 @@ -21163,7 +21163,7 @@ rate(deg/s) objname:StabilizationSettings button:default - buttongroup:8,2 + buttongroup:8 @@ -23312,7 +23312,7 @@ border-radius: 5; fieldname:GyroTau haslimits:no scale:1 - buttongroup:8,20 + buttongroup:8,10 @@ -23361,7 +23361,7 @@ border-radius: 5; fieldname:AccelKp haslimits:no scale:1 - buttongroup:8,20 + buttongroup:8,10 @@ -23410,7 +23410,7 @@ border-radius: 5; fieldname:AccelKi haslimits:no scale:1 - buttongroup:8,20 + buttongroup:8,10 From f0d6f78ba381d550f388bce13a79c258a944a649 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Thu, 2 Aug 2012 12:32:43 +0100 Subject: [PATCH 136/543] GCS- Fixes compile under Win. --- ground/openpilotgcs/src/app/main.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/app/main.cpp b/ground/openpilotgcs/src/app/main.cpp index ff0165fa7..5d117de5a 100644 --- a/ground/openpilotgcs/src/app/main.cpp +++ b/ground/openpilotgcs/src/app/main.cpp @@ -262,8 +262,9 @@ int main(int argc, char **argv) rl.rlim_cur = rl.rlim_max; setrlimit(RLIMIT_NOFILE, &rl); #endif - +#ifdef Q_OS_LINUX QApplication::setAttribute(Qt::AA_X11InitThreads, true); +#endif QApplication::setGraphicsSystem("raster"); SharedTools::QtSingleApplication app((QLatin1String(appNameC)), argc, argv); From 38e392d49e056d76d7ef245f13f0e066a6d551db Mon Sep 17 00:00:00 2001 From: David Ankers Date: Fri, 3 Aug 2012 05:59:20 +1000 Subject: [PATCH 137/543] Update status bargraphs, stab mode is no longer hidden. Soem work to go on other SVGs yet but these looks better than they did. Removed GPS Staus from the top status bar, this will be intergraded in to the PFD --- .../openpilotgcs/dials/default/arm-status.svg | 228 +++- .../dials/default/flightmode-status.svg | 1101 +++++------------ .../openpilotgcs/dials/default/textonly.svg | 219 ++-- .../src/plugins/coreplugin/OpenPilotGCS.xml | 30 +- 4 files changed, 625 insertions(+), 953 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/dials/default/arm-status.svg b/ground/openpilotgcs/share/openpilotgcs/dials/default/arm-status.svg index b72d1cc33..84900ada7 100755 --- a/ground/openpilotgcs/share/openpilotgcs/dials/default/arm-status.svg +++ b/ground/openpilotgcs/share/openpilotgcs/dials/default/arm-status.svg @@ -14,8 +14,8 @@ height="80.827866" id="svg10068" version="1.1" - inkscape:version="0.48.2 r9819" - sodipodi:docname="arm-status-new.svg" + inkscape:version="0.48.3.1 r9886" + sodipodi:docname="arm-status.svg" inkscape:export-filename="H:\Documents\Hobbies\W433\My Gauges\vbat-001.png" inkscape:export-xdpi="103.61" inkscape:export-ydpi="103.61" @@ -1300,6 +1300,156 @@ id="linearGradient3966" xlink:href="#linearGradient3790-4-8" inkscape:collect="always" /> + + + + + + + + + + + + + + + + + + + + + - - - - - - + inkscape:label="#g3319"> + inkscape:label="#rect2985-5" + transform="matrix(0.81679353,0,0,0.88235114,142.08795,-134.58341)" + id="solid_bg" + ry="10.434186" + y="528.80811" + x="79.017357" + height="91.499794" + width="280.11307" + style="fill:url(#linearGradient3312);fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:0;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline;filter:url(#filter4045)" /> + transform="matrix(0.3,0,0,0.3,-0.69,0)" + inkscape:connector-curvature="0" /> - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + image/svg+xml - + Edouard Lafargue @@ -1160,38 +971,12 @@ inkscape:label="Background" id="g2932" inkscape:groupmode="layer" - transform="translate(-205.8687,-331.45166)"> + transform="translate(-205.8687,-331.45166)" + sodipodi:insensitive="true"> - - - - - - + inkscape:label="#g8543" + transform="matrix(0.96748131,0,0,1,6.7388582,0)"> + style="fill:none;stroke:none" /> + diff --git a/ground/openpilotgcs/share/openpilotgcs/dials/default/textonly.svg b/ground/openpilotgcs/share/openpilotgcs/dials/default/textonly.svg index 610ceab72..d159305d2 100755 --- a/ground/openpilotgcs/share/openpilotgcs/dials/default/textonly.svg +++ b/ground/openpilotgcs/share/openpilotgcs/dials/default/textonly.svg @@ -14,7 +14,7 @@ height="80.827866" id="svg10068" version="1.1" - inkscape:version="0.48.2 r9819" + inkscape:version="0.48.3.1 r9886" sodipodi:docname="textonly.svg" inkscape:export-filename="H:\Documents\Hobbies\W433\My Gauges\vbat-001.png" inkscape:export-xdpi="103.61" @@ -1012,50 +1012,6 @@ id="linearGradient3561" xlink:href="#linearGradient3790-4-8" inkscape:collect="always" /> - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - + transform="matrix(0.81679353,0,0,0.88235114,141.83541,-134.83594)" + inkscape:label="#rect2985-5" /> uavGadget - - LineardialGadget - - Flight mode - - uavGadget - - - LineardialGadget - - GPS Sats - - uavGadget - - 1 - @Variant(AAAACQAAAAIAAAACAAAAoAAAAAIAAACk) - splitter + LineardialGadget + + Flight mode + + uavGadget 1 - @Variant(AAAACQAAAAIAAAACAAAAmQAAAAIAAAFC) + @Variant(AAAACQAAAAIAAAACAAAAsQAAAAIAAAEV) splitter 1 - @Variant(AAAACQAAAAIAAAACAAAAmQAAAAIAAAHc) + @Variant(AAAACQAAAAIAAAACAAAArgAAAAIAAAHH) splitter - PfdQmlGadget + PFDGadget - NoTerrain + raw uavGadget From 64ab589c1bbbb89137a049c231bd52f3bcf17f39 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Fri, 3 Aug 2012 06:28:08 +1000 Subject: [PATCH 138/543] Fix from Berkely to the Uploader.ui --- ground/openpilotgcs/src/plugins/uploader/uploader.ui | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader.ui b/ground/openpilotgcs/src/plugins/uploader/uploader.ui index 540d69302..06c62f147 100644 --- a/ground/openpilotgcs/src/plugins/uploader/uploader.ui +++ b/ground/openpilotgcs/src/plugins/uploader/uploader.ui @@ -40,7 +40,7 @@ through serial or USB) Boots the system. Only useful if the system is halted -(mainboard blue LED blinking slowly, orange LED off) +(mainboard blue LED blinking slowly, green LED on) If telemetry is not running, select the link using the dropdown menu on the right. @@ -217,7 +217,7 @@ p, li { white-space: pre-wrap; } - + From 4357f092a9aa6c0219a84ee415efce29dbaf57d0 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Fri, 3 Aug 2012 08:15:57 +1000 Subject: [PATCH 139/543] Remove a couple of artifact numbers from the PFD, start work on spacing and layout. --- .../share/openpilotgcs/pfd/default/pfd.svg | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/pfd.svg b/ground/openpilotgcs/share/openpilotgcs/pfd/default/pfd.svg index 6313bf1df..95724c8b8 100755 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/pfd.svg +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/pfd.svg @@ -14,7 +14,7 @@ height="707.56323" id="svg2" version="1.1" - inkscape:version="0.48.1 " + inkscape:version="0.48.3.1 r9886" sodipodi:docname="pfd.svg" style="display:inline" inkscape:export-filename="H:\Documents\Hobbies\OpenPilot\SVN\artwork\PFD-2.png" @@ -1616,13 +1616,13 @@ inkscape:pageopacity="0.0" inkscape:pageshadow="2" inkscape:zoom="0.73067675" - inkscape:cx="305.98471" + inkscape:cx="431.15187" inkscape:cy="372.16908" inkscape:document-units="px" inkscape:current-layer="layer3" showgrid="false" - inkscape:window-width="1366" - inkscape:window-height="706" + inkscape:window-width="1440" + inkscape:window-height="838" inkscape:window-x="-8" inkscape:window-y="-8" inkscape:window-maximized="1" @@ -1715,7 +1715,7 @@ inkscape:groupmode="layer" id="layer1" transform="translate(230.4171,-254.91153)" - style="display:inline" + style="display:none" sodipodi:insensitive="true"> Date: Fri, 3 Aug 2012 09:06:02 +1000 Subject: [PATCH 140/543] Needed a clean up and some things added. There are many more to add for sure, putting it in the branch as it might get noticed and people can add what they have done, plus fill in some blanks / add some more cool future Milestones. There are also things like Stac's flight on Rockets to add. --- MILESTONES.txt | 67 +++++++++++++++++++++++++++++++++++++++----------- 1 file changed, 53 insertions(+), 14 deletions(-) diff --git a/MILESTONES.txt b/MILESTONES.txt index 14242d2f2..34e846260 100644 --- a/MILESTONES.txt +++ b/MILESTONES.txt @@ -147,6 +147,7 @@ C: Sergey Solodennikov (alconaft43) D: August 2011 V: http://www.youtube.com/watch?v=8SrfIS7OkB4 + M: First CopterControl Return to Base Fixed Wing C: Eric Price (Corvus Corax) D: August 2011 @@ -157,13 +158,23 @@ C: Anders Johansson (dezent) D: November 2011 V: http://www.youtube.com/watch?v=Xfas2TUhOPw -M: First OpenPilot over 1km FixedWing navigation flight +M: First CopterControl over 1km FixedWing navigation flight C: Eric Price (Corvus Corax) D: December 2011 V: http://www.youtube.com/watch?v=nWNWuUiUTNg + +M: First successful flight using the GCS only and no RC TX +C: +D: +V: + +M: First successful flight using just a mobile phone +C: Jose (please complete details), demoed in Portugal +D: +V: -M: First Altitude Hold using Sonar +M: First Revo Altitude Hold using Sonar C: D: V: @@ -178,17 +189,45 @@ C: D: V: +M: First Revo Navigated flight on a FixedWing +C: It got done somewhere along the line, likely Corvus. + +M: First Revo Navigated flight on a MultiRotor +C: It got done somewhere along the line, James or Sami + +M: First Revo Navigated flight on a Heli +C: +D: +V: + +M: First Revo 1km Navigated flight on a MultiRotor +C: +D: +V: + +M: First Revo 5km Navigated flight on a MultiRotor +C: +D: +V: + +M: First Revo 5km Navigated flight on a FixedWing +C: +D: +V: + +M: First Revo 1km Navigated flight on a Heli +C: +D: +V: + +M: First Revo 5km Navigated flight on a Heli +C: +D: +V: + +M: First use of the Magic Waypoint feature +C: +D: +V: -An incomplete list of some future Milestones is below: -* First Helicopter flight with OpenPilot Pro -* First fixed wing navigation flight on CopterControl -* First successful flight using the GCS only and no RC TX -* First use of Magic Waypoint -* First Flybarless Helicopter flight with OpenPilot Pro -* First fixed wing navigation flight -* First Multirotor navigation flight -* First Helicopter navigation flight -* First over 5km navigation flight -* First "Follow Me" navigation flight -* First Channel Crossing with OpenPilot From 73a4c605542866ffb30a4afa82b5a250a4dbc920 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Fri, 3 Aug 2012 09:09:37 +1000 Subject: [PATCH 141/543] Add the auto take off and landing empty milestones. These sould be a planned autolandings, controlled flight in terrain does not count. :) --- MILESTONES.txt | 29 +++++++++++++++++++++++++++++ 1 file changed, 29 insertions(+) diff --git a/MILESTONES.txt b/MILESTONES.txt index 34e846260..d46c1820d 100644 --- a/MILESTONES.txt +++ b/MILESTONES.txt @@ -230,4 +230,33 @@ C: D: V: +M: First Auto landing on a fixed Wing using CC +C: +D: +V: + +M: First Auto landing on a fixed Wing using Revo +C: +D: +V: + +M: First Auto take-off on a MultiRotor using Revo +C: +D: +V: + +M: First Auto landing on a MultiRotor using Revo +C: +D: +V: + +M: First Auto take-off on a Heli using Revo +C: +D: +V: + +M: First Auto landing on a Heli using Revo +C: +D: +V: From 63e5fc80ce2e93b36a61c83a65cd61eec6731d61 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Thu, 2 Aug 2012 16:11:18 -0700 Subject: [PATCH 142/543] TelemetryMonitorWidget: Alpha version with 12 dots. --- .../plugins/coreplugin/connectionmanager.cpp | 21 ++- .../plugins/coreplugin/connectionmanager.h | 9 +- .../src/plugins/coreplugin/core.qrc | 1 + .../src/plugins/coreplugin/coreplugin.pro | 6 +- .../coreplugin/telemetrymonitorwidget.cpp | 145 ++++++++++++++++++ .../coreplugin/telemetrymonitorwidget.h | 53 +++++++ .../src/plugins/uavtalk/telemetrymonitor.cpp | 7 + .../src/plugins/uavtalk/telemetrymonitor.h | 1 + 8 files changed, 239 insertions(+), 4 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp create mode 100644 ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.h diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp index eb3db6d50..9006b691f 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp @@ -31,9 +31,9 @@ #include #include #include - #include "qextserialport/src/qextserialenumerator.h" #include "qextserialport/src/qextserialport.h" + #include #include #include @@ -59,6 +59,10 @@ ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow, QTabWidge QHBoxLayout *layout = new QHBoxLayout; layout->setSpacing(5); layout->setContentsMargins(5,5,5,5); + + m_monitor = new TelemetryMonitorWidget(this); + layout->addWidget(m_monitor); + layout->addWidget(new QLabel(tr("Connections:"))); m_availableDevList = new QComboBox; @@ -140,6 +144,10 @@ bool ConnectionManager::connectDevice() emit deviceConnected(m_ioDev); m_connectBtn->setText("Disconnect"); m_availableDevList->setEnabled(false); + + // tell the monitor we're connected + m_monitor->connect(); + return true; } @@ -168,6 +176,9 @@ bool ConnectionManager::disconnectDevice() qDebug() << "Exception: m_connectionDevice.connection->closeDevice(" << m_connectionDevice.devName << ")"; } + //tell the monitor we're disconnected + m_monitor->disconnect(); + m_connectionDevice.connection = NULL; m_ioDev = NULL; @@ -239,6 +250,14 @@ void ConnectionManager::onConnectClicked() } } +/** +* Slot called when the telemetry rates are updated +*/ +void ConnectionManager::telemetryUpdated(double txRate, double rxRate) +{ + m_monitor->updateTelemetry(txRate, rxRate); +} + /** * Find a device by its displayed (visible on screen) name */ diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h index 90f779aed..4ed3e9530 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h @@ -32,6 +32,8 @@ #include #include "mainwindow.h" #include "generalsettings.h" +#include "telemetrymonitorwidget.h" + #include #include #include @@ -63,7 +65,6 @@ struct devListItem QString displayName; }; - class CORE_EXPORT ConnectionManager : public QWidget { Q_OBJECT @@ -89,6 +90,9 @@ signals: void deviceConnected(QIODevice *dev); void deviceAboutToDisconnect(); +public slots: + void telemetryUpdated(double txRate, double rxRate); + private slots: void objectAdded(QObject *obj); void aboutToRemoveObject(QObject *obj); @@ -105,6 +109,9 @@ protected: QLinkedList m_devList; QList m_connectionsList; + //tx/rx telemetry monitor + TelemetryMonitorWidget* m_monitor; + //currently connected connection plugin devListItem m_connectionDevice; diff --git a/ground/openpilotgcs/src/plugins/coreplugin/core.qrc b/ground/openpilotgcs/src/plugins/coreplugin/core.qrc index d65e51376..8d559b2ce 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/core.qrc +++ b/ground/openpilotgcs/src/plugins/coreplugin/core.qrc @@ -62,5 +62,6 @@ OpenPilotGCS.xml images/helpicon.svg images/cpu.png + images/tx-rx.svg diff --git a/ground/openpilotgcs/src/plugins/coreplugin/coreplugin.pro b/ground/openpilotgcs/src/plugins/coreplugin/coreplugin.pro index 8c73b00ef..4ba5715c9 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/coreplugin.pro +++ b/ground/openpilotgcs/src/plugins/coreplugin/coreplugin.pro @@ -62,7 +62,8 @@ SOURCES += mainwindow.cpp \ uavgadgetdecorator.cpp \ workspacesettings.cpp \ uavconfiginfo.cpp \ - authorsdialog.cpp + authorsdialog.cpp \ + telemetrymonitorwidget.cpp HEADERS += mainwindow.h \ tabpositionindicator.h \ fancyactionbar.h \ @@ -122,7 +123,8 @@ HEADERS += mainwindow.h \ workspacesettings.h \ uavconfiginfo.h \ authorsdialog.h \ - iconfigurableplugin.h + iconfigurableplugin.h \ + telemetrymonitorwidget.h FORMS += dialogs/settingsdialog.ui \ dialogs/shortcutsettings.ui \ generalsettings.ui \ diff --git a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp new file mode 100644 index 000000000..47a8d1c66 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp @@ -0,0 +1,145 @@ +#include "telemetrymonitorwidget.h" + +#include +#include +#include + +TelemetryMonitorWidget::TelemetryMonitorWidget(QWidget *parent) : QGraphicsView(parent) +{ + setMinimumSize(160,60); + setMaximumSize(160,60); + setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); + setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + setFrameStyle(QFrame::NoFrame); + setBackgroundBrush(Qt::transparent); + + QGraphicsScene *scene = new QGraphicsScene(0,0,160,60, this); + scene->setBackgroundBrush(Qt::transparent); + + QSvgRenderer *renderer = new QSvgRenderer(); + if (renderer->load(QString(":/core/images/tx-rx.svg"))) { + graph = new QGraphicsSvgItem(); + graph->setSharedRenderer(renderer); + graph->setElementId("txrxBackground"); + + QString name; + QGraphicsSvgItem* pt; + + for (int i=0; ielementExists(name)) { + pt = new QGraphicsSvgItem(); + pt->setSharedRenderer(renderer); + pt->setElementId(name); + pt->setParentItem(graph); + txNodes.append(pt); + } + + name = QString("rx%0").arg(i); + if (renderer->elementExists(name)) { + pt = new QGraphicsSvgItem(); + pt->setSharedRenderer(renderer); + pt->setElementId(name); + pt->setParentItem(graph); + rxNodes.append(pt); + } + } + + scene->addItem(graph); + scene->setSceneRect(graph->boundingRect()); + setScene(scene); + } + + connected = false; + txValue = 0.0; + rxValue = 0.0; + + setMin(0.0); + setMax(1200.0); + + showTelemetry(); +} + +TelemetryMonitorWidget::~TelemetryMonitorWidget() +{ + while (!txNodes.isEmpty()) + delete txNodes.takeFirst(); + + while (!rxNodes.isEmpty()) + delete rxNodes.takeFirst(); +} + +void TelemetryMonitorWidget::connect() +{ + connected = true; + + //flash the lights + updateTelemetry(maxValue, maxValue); +} + +void TelemetryMonitorWidget::disconnect() +{ + //flash the lights + updateTelemetry(maxValue, maxValue); + + connected = false; + updateTelemetry(0.0,0.0); +} +/*! + \brief Called by the UAVObject which got updated + + Updates the numeric value and/or the icon if the dial wants this. + */ +void TelemetryMonitorWidget::updateTelemetry(double txRate, double rxRate) +{ + txValue = txRate; + rxValue = rxRate; + + showTelemetry(); +} + +// Converts the value into an percentage: +// this enables smooth movement in moveIndex below +void TelemetryMonitorWidget::showTelemetry() +{ + txIndex = (txValue-minValue)/(maxValue-minValue) * NODE_NUMELEM; + rxIndex = (rxValue-minValue)/(maxValue-minValue) * NODE_NUMELEM; + + if (connected) + this->setToolTip(QString("Tx: %0 bytes/sec\nRx: %1 bytes/sec").arg(txValue).arg(rxValue)); + else + this->setToolTip(QString("Disconnected")); + + QGraphicsItem* txNode; + QGraphicsItem* rxNode; + + for (int i=0; i < NODE_NUMELEM; i++) { + txNode = txNodes.at(i); + txNode->setPos((i*(txNode->boundingRect().width() + 8)) + 8, (txNode->boundingRect().height()/2) - 2); + txNode->setVisible(connected && i < txIndex); + txNode->update(); + + rxNode = rxNodes.at(i); + rxNode->setPos((i*(rxNode->boundingRect().width() + 8)) + 8, (rxNode->boundingRect().height()*2) - 2); + rxNode->setVisible(connected && i < rxIndex); + rxNode->update(); + } + update(); +} + +void TelemetryMonitorWidget::showEvent(QShowEvent *event) +{ + Q_UNUSED(event); + + fitInView(graph, Qt::KeepAspectRatio); +} + +void TelemetryMonitorWidget::resizeEvent(QResizeEvent* event) +{ + Q_UNUSED(event); + + graph->setPos(0,-90); + fitInView(graph, Qt::KeepAspectRatio); +} + diff --git a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.h b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.h new file mode 100644 index 000000000..b5e335398 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.h @@ -0,0 +1,53 @@ +#ifndef TELEMETRYMONITORWIDGET_H +#define TELEMETRYMONITORWIDGET_H + +#include +#include +#include +#include +#include +#include + +class TelemetryMonitorWidget : public QGraphicsView +{ + Q_OBJECT +public: + explicit TelemetryMonitorWidget(QWidget *parent = 0); + ~TelemetryMonitorWidget(); + + void setMin(double min) { minValue = min;} + double getMin() { return minValue; } + void setMax(double max) { maxValue = max;} + double getMax() { return maxValue; } + + //number of tx/rx nodes in the graph + static const int NODE_NUMELEM = 12; + +signals: + +public slots: + void connect(); + void disconnect(); + + void updateTelemetry(double txRate, double rxRate); + void showTelemetry(); + +protected: + void showEvent(QShowEvent *event); + void resizeEvent(QResizeEvent *event); + +private: + QGraphicsSvgItem *graph; + QList txNodes; + QList rxNodes; + + bool connected; + double txIndex; + double txValue; + double rxIndex; + double rxValue; + double minValue; + double maxValue; +}; + +#endif // TELEMETRYMONITORWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/uavtalk/telemetrymonitor.cpp b/ground/openpilotgcs/src/plugins/uavtalk/telemetrymonitor.cpp index 881e1bc7d..00c997374 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/telemetrymonitor.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/telemetrymonitor.cpp @@ -27,6 +27,8 @@ #include "telemetrymonitor.h" #include "qxtlogger.h" +#include "coreplugin/connectionmanager.h" +#include "coreplugin/icore.h" /** * Constructor @@ -52,6 +54,9 @@ TelemetryMonitor::TelemetryMonitor(UAVObjectManager* objMngr, Telemetry* tel) statsTimer = new QTimer(this); connect(statsTimer, SIGNAL(timeout()), this, SLOT(processStatsUpdates())); statsTimer->start(STATS_CONNECT_PERIOD_MS); + + Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); + connect(this,SIGNAL(telemetryUpdated(double,double)),cm,SLOT(telemetryUpdated(double,double))); } TelemetryMonitor::~TelemetryMonitor() { @@ -232,6 +237,8 @@ void TelemetryMonitor::processStatsUpdates() } } + emit telemetryUpdated((double)gcsStats.TxDataRate, (double)gcsStats.RxDataRate); + // Set data gcsStatsObj->setData(gcsStats); diff --git a/ground/openpilotgcs/src/plugins/uavtalk/telemetrymonitor.h b/ground/openpilotgcs/src/plugins/uavtalk/telemetrymonitor.h index 05e54706f..5d480a86e 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/telemetrymonitor.h +++ b/ground/openpilotgcs/src/plugins/uavtalk/telemetrymonitor.h @@ -51,6 +51,7 @@ public: signals: void connected(); void disconnected(); + void telemetryUpdated(double txRate, double rxRate); public slots: void transactionCompleted(UAVObject* obj, bool success); From 9ebf6d916af8ac72aa913e8f00499b0a4676f7f5 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Thu, 2 Aug 2012 19:33:20 -0700 Subject: [PATCH 143/543] TelemetryMonitorWidget: tx/rx labels, 7 nodes, tx/rx rate text. --- .../src/plugins/coreplugin/images/tx-rx.svg | 390 ++++++++++++++++++ .../coreplugin/telemetrymonitorwidget.cpp | 33 +- .../coreplugin/telemetrymonitorwidget.h | 4 +- 3 files changed, 420 insertions(+), 7 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/coreplugin/images/tx-rx.svg diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/tx-rx.svg b/ground/openpilotgcs/src/plugins/coreplugin/images/tx-rx.svg new file mode 100644 index 000000000..42d0f6d30 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/coreplugin/images/tx-rx.svg @@ -0,0 +1,390 @@ + + + + + + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + Tx + Tx + Rx + + + + + + + + + + + + 0 b/s + + + + + + + + + + 0 b/s + + diff --git a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp index 47a8d1c66..ad17b3580 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp @@ -2,19 +2,20 @@ #include #include +#include #include TelemetryMonitorWidget::TelemetryMonitorWidget(QWidget *parent) : QGraphicsView(parent) { - setMinimumSize(160,60); - setMaximumSize(160,60); + setMinimumSize(160,80); + setMaximumSize(160,80); setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); setFrameStyle(QFrame::NoFrame); setBackgroundBrush(Qt::transparent); - QGraphicsScene *scene = new QGraphicsScene(0,0,160,60, this); + QGraphicsScene *scene = new QGraphicsScene(0,0,160,80, this); scene->setBackgroundBrush(Qt::transparent); QSvgRenderer *renderer = new QSvgRenderer(); @@ -47,6 +48,19 @@ TelemetryMonitorWidget::TelemetryMonitorWidget(QWidget *parent) : QGraphicsView( } scene->addItem(graph); + + txSpeed = new QGraphicsTextItem(); + txSpeed->setDefaultTextColor(Qt::white); + txSpeed->setFont(QFont("Helvetica",22,2)); + txSpeed->setParentItem(graph); + scene->addItem(txSpeed); + + rxSpeed = new QGraphicsTextItem(); + rxSpeed->setDefaultTextColor(Qt::white); + rxSpeed->setFont(QFont("Helvetica",22,2)); + rxSpeed->setParentItem(graph); + scene->addItem(rxSpeed); + scene->setSceneRect(graph->boundingRect()); setScene(scene); } @@ -116,15 +130,22 @@ void TelemetryMonitorWidget::showTelemetry() for (int i=0; i < NODE_NUMELEM; i++) { txNode = txNodes.at(i); - txNode->setPos((i*(txNode->boundingRect().width() + 8)) + 8, (txNode->boundingRect().height()/2) - 2); + txNode->setPos((i*(txNode->boundingRect().width() + 8)) + 60, (txNode->boundingRect().height()/2) - 2); txNode->setVisible(connected && i < txIndex); txNode->update(); rxNode = rxNodes.at(i); - rxNode->setPos((i*(rxNode->boundingRect().width() + 8)) + 8, (rxNode->boundingRect().height()*2) - 2); + rxNode->setPos((i*(rxNode->boundingRect().width() + 8)) + 60, (rxNode->boundingRect().height()*2) - 2); rxNode->setVisible(connected && i < rxIndex); rxNode->update(); } + + txSpeed->setPos(graph->boundingRect().right() - 100, txNodes.at(0)->pos().y() - 10); + txSpeed->setPlainText(QString("%0").arg(txValue)); + + rxSpeed->setPos(graph->boundingRect().right() - 100, rxNodes.at(0)->pos().y() - 10); + rxSpeed->setPlainText(QString("%0").arg(rxValue)); + update(); } @@ -139,7 +160,7 @@ void TelemetryMonitorWidget::resizeEvent(QResizeEvent* event) { Q_UNUSED(event); - graph->setPos(0,-90); + graph->setPos(0,-100); fitInView(graph, Qt::KeepAspectRatio); } diff --git a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.h b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.h index b5e335398..dc7b1a1f9 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.h @@ -21,7 +21,7 @@ public: double getMax() { return maxValue; } //number of tx/rx nodes in the graph - static const int NODE_NUMELEM = 12; + static const int NODE_NUMELEM = 7; signals: @@ -38,6 +38,8 @@ protected: private: QGraphicsSvgItem *graph; + QGraphicsTextItem *txSpeed; + QGraphicsTextItem *rxSpeed; QList txNodes; QList rxNodes; From f5bd860be104a486e6886bdf4d1eb9e0638fe16a Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Thu, 2 Aug 2012 20:32:55 -0700 Subject: [PATCH 144/543] TelemetryWidget: tweek datarate text locations. --- .../src/plugins/coreplugin/telemetrymonitorwidget.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp index ad17b3580..0f96c06e5 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp @@ -140,11 +140,11 @@ void TelemetryMonitorWidget::showTelemetry() rxNode->update(); } - txSpeed->setPos(graph->boundingRect().right() - 100, txNodes.at(0)->pos().y() - 10); - txSpeed->setPlainText(QString("%0").arg(txValue)); + txSpeed->setPos(graph->boundingRect().right() - 110, txNodes.at(0)->pos().y() - 10); + txSpeed->setPlainText(QString("%0").arg(connected ? txValue : 0.0)); - rxSpeed->setPos(graph->boundingRect().right() - 100, rxNodes.at(0)->pos().y() - 10); - rxSpeed->setPlainText(QString("%0").arg(rxValue)); + rxSpeed->setPos(graph->boundingRect().right() - 110, rxNodes.at(0)->pos().y() - 10); + rxSpeed->setPlainText(QString("%0").arg(connected ? rxValue : 0.0)); update(); } From 5320a73adc24d809b09f56474805d8ba18d8c59b Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Thu, 2 Aug 2012 21:19:25 -0700 Subject: [PATCH 145/543] TelemetryWidget: tweeks and bugfixes. --- .../coreplugin/telemetrymonitorwidget.cpp | 33 +++++++++++-------- .../coreplugin/telemetrymonitorwidget.h | 4 +-- 2 files changed, 21 insertions(+), 16 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp index 0f96c06e5..19f5aaf00 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp @@ -125,25 +125,30 @@ void TelemetryMonitorWidget::showTelemetry() else this->setToolTip(QString("Disconnected")); - QGraphicsItem* txNode; - QGraphicsItem* rxNode; + int i; + int nodeMargin = 8; + int leftMargin = 60; + QGraphicsItem* node; - for (int i=0; i < NODE_NUMELEM; i++) { - txNode = txNodes.at(i); - txNode->setPos((i*(txNode->boundingRect().width() + 8)) + 60, (txNode->boundingRect().height()/2) - 2); - txNode->setVisible(connected && i < txIndex); - txNode->update(); - - rxNode = rxNodes.at(i); - rxNode->setPos((i*(rxNode->boundingRect().width() + 8)) + 60, (rxNode->boundingRect().height()*2) - 2); - rxNode->setVisible(connected && i < rxIndex); - rxNode->update(); + for (i=0; i < txNodes.count(); i++) { + node = txNodes.at(i); + node->setPos((i*(node->boundingRect().width() + nodeMargin)) + leftMargin, (node->boundingRect().height()/2) - 2); + node->setVisible(connected && i < txIndex); + node->update(); } - txSpeed->setPos(graph->boundingRect().right() - 110, txNodes.at(0)->pos().y() - 10); + for (i=0; i < rxNodes.count(); i++) { + node = rxNodes.at(i); + node->setPos((i*(node->boundingRect().width() + nodeMargin)) + leftMargin, (node->boundingRect().height()*2) - 2); + node->setVisible(connected && i < rxIndex); + node->update(); + } + + QRectF rect = graph->boundingRect(); + txSpeed->setPos(rect.right() - 110, rect.top()); txSpeed->setPlainText(QString("%0").arg(connected ? txValue : 0.0)); - rxSpeed->setPos(graph->boundingRect().right() - 110, rxNodes.at(0)->pos().y() - 10); + rxSpeed->setPos(rect.right() - 110, rect.top() + (rect.height() / 2)); rxSpeed->setPlainText(QString("%0").arg(connected ? rxValue : 0.0)); update(); diff --git a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.h b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.h index dc7b1a1f9..803362230 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.h @@ -38,8 +38,8 @@ protected: private: QGraphicsSvgItem *graph; - QGraphicsTextItem *txSpeed; - QGraphicsTextItem *rxSpeed; + QPointer txSpeed; + QPointer rxSpeed; QList txNodes; QList rxNodes; From 4de9cd89f75dd0fe013a6e931afbe82fe454d1b9 Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Thu, 2 Aug 2012 22:14:39 -0700 Subject: [PATCH 146/543] micro GCs layout, redesigned layouts again for stabi screen --- .../src/plugins/config/stabilization.ui | 14787 +++++++--------- 1 file changed, 6540 insertions(+), 8247 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 4fe78abea..84ebef74b 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,8 +6,8 @@ 0 0 - 786 - 950 + 992 + 885 @@ -453,9 +453,6 @@ false - - 6 - @@ -597,3318 +594,18 @@ 0 0 - 764 - 818 + 962 + 754 - - - - - - 0 - 0 - - - - - 0 - 195 - - - - - 16777215 - 181 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - Attitude Stabilization (Outer Loop) - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - 4 - - - - - - 0 - 0 - - - - Qt::StrongFocus - - - - - - Link Roll and Pitch - - - - - - - Qt::Horizontal - - - QSizePolicy::MinimumExpanding - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - Reset all values to GCS defaults - - - - - - Default - - - - button:default - buttongroup:2 - - - - - - - - - - - 0 - 0 - - - - - 0 - 131 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 78 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Kp - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 100 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 200 - - - 200 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Ki - scale:0.1 - haslimits:yes - buttongroup:2,10 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - + + + 12 + + - + 0 0 @@ -3931,11 +628,8 @@ border-radius: 5; Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - 6 - - + + 4 @@ -4017,7 +711,7 @@ border-radius: 5; - + @@ -4466,7 +1160,7 @@ border-radius: 5; true - + @@ -6762,98 +3456,10 @@ value as the Kp. - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 180 - - - - - - - - - 0 - 80 - - - - - - - - - - - 0 - 0 - - - - - 300 - 20 - - - - When the throttle is low, zero the intergral term to prevent intergral wind-up - - - - - - Zero the integral when throttle is low - - - - objname:StabilizationSettings - fieldname:LowThrottleZeroIntegral - - - - - - - - - 0 - 0 - - - - - 136 - 20 - - - - If you check this, the GCS will udpate the stabilization factors -automatically every 300ms, which will help for fast tuning. - - - - - - Update in real time - - - - - - - - + + - + 0 0 @@ -6861,13 +3467,13 @@ automatically every 300ms, which will help for fast tuning. 0 - 225 + 195 16777215 - 211 + 181 @@ -7384,20 +3990,42 @@ automatically every 300ms, which will help for fast tuning. + + false + - Stick Range and Limits + Attitude Stabilization (Outer Loop) Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - + - + 4 - + + + + 0 + 0 + + + + Qt::StrongFocus + + + + + + Link Roll and Pitch + + + + + Qt::Horizontal @@ -7413,7 +4041,7 @@ automatically every 300ms, which will help for fast tuning. - + 0 @@ -7438,7 +4066,7 @@ automatically every 300ms, which will help for fast tuning. button:default - buttongroup:3 + buttongroup:2 @@ -7446,7 +4074,7 @@ automatically every 300ms, which will help for fast tuning. - + 0 @@ -7456,13 +4084,7 @@ automatically every 300ms, which will help for fast tuning. 0 - 161 - - - - - 16777215 - 180 + 131 @@ -7892,9 +4514,9 @@ automatically every 300ms, which will help for fast tuning. true - + - + 0 @@ -8443,8 +5065,8 @@ border-radius: 5; - - + + 0 @@ -8993,8 +5615,8 @@ border-radius: 5; - - + + 0 @@ -9544,7 +6166,7 @@ border-radius: 5; - + 0 @@ -9553,16 +6175,15 @@ border-radius: 5; - 69 - 29 + 78 + 16 - Full Stick -Angle (deg) + Proportional Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter @@ -9570,7 +6191,7 @@ Angle (deg) - + 0 @@ -9590,7 +6211,7 @@ Angle (deg) - 180 + 100 50 @@ -9607,16 +6228,17 @@ Angle (deg) objname:StabilizationSettings - fieldname:RollMax + fieldname:RollPI + element:Kp + scale:0.1 haslimits:yes - scale:1.0 - buttongroup:3,10 + buttongroup:2,10 - + 50 @@ -9633,40 +6255,25 @@ Angle (deg) Qt::StrongFocus - 180 + 200 - 180 + 200 objname:StabilizationSettings - fieldname:RollMax + fieldname:RollPI + element:Kp + scale:0.1 haslimits:yes - scale:1.0 - buttongroup:3,10 + buttongroup:2,10 - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 3 - 22 - - - - - - + 0 @@ -9686,7 +6293,7 @@ Angle (deg) - 180 + 100 50 @@ -9703,66 +6310,52 @@ Angle (deg) objname:StabilizationSettings - fieldname:PitchMax + fieldname:PitchPI + element:Kp + scale:0.1 haslimits:yes - scale:1.0 - buttongroup:3,10 + buttongroup:2,10 + + + + + + + + + 50 + 22 + + + + + 50 + 22 + + + + Qt::StrongFocus + + + 200 + + + 200 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Kp + scale:0.1 + haslimits:yes + buttongroup:2,10 - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 180 - - - 180 - - - - objname:StabilizationSettings - fieldname:PitchMax - haslimits:yes - scale:1.0 - buttongroup:3,10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 3 - 22 - - - - - - + 0 @@ -9782,7 +6375,7 @@ Angle (deg) - 180 + 100 50 @@ -9799,16 +6392,17 @@ Angle (deg) objname:StabilizationSettings - fieldname:YawMax + fieldname:YawPI + element:Kp + scale:0.1 haslimits:yes - scale:1.0 - buttongroup:3,10 + buttongroup:2,10 - - + + 50 @@ -9825,42 +6419,36 @@ Angle (deg) Qt::StrongFocus - 180 + 200 - 180 + 200 objname:StabilizationSettings - fieldname:YawMax + fieldname:YawPI + element:Kp + scale:0.1 haslimits:yes - scale:1.0 - buttongroup:3,10 + buttongroup:2,10 - + 0 0 - - - 69 - 29 - - - Full Stick -Rate (deg/s) + Integral Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter @@ -9868,7 +6456,7 @@ Rate (deg/s) - + 0 @@ -9888,7 +6476,7 @@ Rate (deg/s) - 500 + 100 50 @@ -9905,17 +6493,17 @@ Rate (deg/s) objname:StabilizationSettings - fieldname:ManualRate - element:Roll + fieldname:RollPI + element:Ki + scale:0.1 haslimits:yes - scale:1 - buttongroup:3,10 + buttongroup:2,10 - + 50 @@ -9932,72 +6520,72 @@ Rate (deg/s) Qt::StrongFocus - 500 + 200 - 180 + 200 objname:StabilizationSettings - fieldname:ManualRate - element:Roll + fieldname:RollPI + element:Ki + scale:0.1 haslimits:yes - scale:1 - buttongroup:3,10 + buttongroup:2,10 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Qt::StrongFocus + + + + + + 100 + + + 50 + + + Qt::Horizontal + + + QSlider::TicksBelow + + + 25 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Ki + scale:0.1 + haslimits:yes + buttongroup:2,10 - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 500 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Pitch - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - + 50 @@ -10014,197 +6602,7 @@ Rate (deg/s) Qt::StrongFocus - 500 - - - 180 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Pitch - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 500 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Yaw - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 500 - - - 180 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Yaw - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 0 - 0 - - - - - 69 - 29 - - - - - - - Max Rate in -Attitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 500 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Roll - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 500 + 200 200 @@ -10212,17 +6610,17 @@ Attitude objname:StabilizationSettings - fieldname:MaximumRate - element:Roll + fieldname:PitchPI + element:Ki + scale:0.1 haslimits:yes - scale:1 - buttongroup:3,10 + buttongroup:2,10 - - + + 0 @@ -10242,7 +6640,7 @@ Attitude - 500 + 100 50 @@ -10259,17 +6657,17 @@ Attitude objname:StabilizationSettings - fieldname:MaximumRate - element:Pitch + fieldname:YawPI + element:Ki + scale:0.1 haslimits:yes - scale:1 - buttongroup:3,10 + buttongroup:2,10 - - + + 50 @@ -10286,7 +6684,7 @@ Attitude Qt::StrongFocus - 500 + 200 200 @@ -10294,99 +6692,17 @@ Attitude objname:StabilizationSettings - fieldname:MaximumRate - element:Pitch + fieldname:YawPI + element:Ki + scale:0.1 haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - Qt::StrongFocus - - - - - - 500 - - - 50 - - - Qt::Horizontal - - - QSlider::TicksBelow - - - 25 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Yaw - haslimits:yes - scale:1 - buttongroup:3,10 - - - - - - - - - 50 - 22 - - - - - 50 - 22 - - - - Qt::StrongFocus - - - 500 - - - 200 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Yaw - haslimits:yes - scale:1 - buttongroup:3,10 + buttongroup:2,10 - + Qt::Horizontal @@ -10398,8 +6714,8 @@ Attitude - - + + Qt::Horizontal @@ -10412,7 +6728,7 @@ Attitude - + Qt::Horizontal @@ -10424,8 +6740,8 @@ Attitude - - + + Qt::Horizontal @@ -10443,8 +6759,8 @@ Attitude - - + + Qt::Vertical @@ -10453,12 +6769,77 @@ Attitude - 10 + 20 12 + + + + + 0 + 0 + + + + + 0 + 62 + + + + Integral + + + + + + + 0 + 0 + + + + + 300 + 20 + + + + When the throttle is low, zero the intergral term to prevent intergral wind-up + + + + + + Zero the integral when throttle is low + + + + objname:StabilizationSettings + fieldname:LowThrottleZeroIntegral + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + @@ -10553,14 +6934,3300 @@ Attitude 0 0 - 748 - 821 + 962 + 754 true - + + + + + + 0 + 0 + + + + + 0 + 230 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + Stick Range and Limits + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + 6 + + + + + Qt::Horizontal + + + QSizePolicy::Expanding + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:6 + + + + + + + + + + + 0 + 0 + + + + + 0 + 160 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + 0 + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:PitchMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 128 + 16 + + + + + 16777215 + 16777215 + + + + + + + Max rate attitude (deg/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:YawMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Pitch + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Full stick angle (deg) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Pitch + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 60 + 16 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:RollMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaximumRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + Full stick rate (deg/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + @@ -11614,12 +11281,37 @@ Attitude true - + 2 - - + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + Qt::Horizontal @@ -11628,12 +11320,171 @@ Attitude - 110 - 13 + 10 + 10 + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same +value as the Kp. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. +Then lower the value by 20% or so. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + @@ -12184,6 +12035,73 @@ border-radius: 5; + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same +value as the Kp. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + @@ -12734,6 +12652,306 @@ border-radius: 5; + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. +Then lower the value by 20% or so. + +You can usually go for higher values for Yaw factors. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. +Then lower the value by 20% or so. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same +value as the Kp. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 58 + 0 + + + + + 16777215 + 16777215 + + + + + + + Derivative + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 60 + 13 + + + + @@ -13284,735 +13502,6 @@ border-radius: 5; - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - -You can usually go for higher values for Yaw factors. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 58 - 0 - - - - - 16777215 - 16777215 - - - - - - - Derivative - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 50 - 0 - - - - - 16777215 - 16777215 - - - - - - - ILimit - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:4,20 - - - - @@ -14030,7 +13519,7 @@ value as the Kp. 0 - 200 + 210 @@ -15075,25 +14564,9 @@ value as the Kp. true - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 110 - 13 - - - - - - + + + 0 @@ -15635,7 +15108,7 @@ color: rgb(255, 255, 255); border-radius: 5; - Roll + Yaw Qt::AlignCenter @@ -16192,737 +15665,21 @@ border-radius: 5; - - - - - 0 - 0 - + + + + Qt::Horizontal - + + QSizePolicy::Preferred + + - 0 - 16 + 60 + 13 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - + @@ -16940,1413 +15697,8 @@ border-radius: 5; - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 50 - 0 - - - - - 16777215 - 16777215 - - - - - - - ILimit - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:ILimit - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:ILimit - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:ILimit - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - - - - - - - 0 - 0 - - - - - 0 - 230 - - - - - 16777215 - 16777215 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - Stick Range and Limits - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - 6 - - - - - Qt::Horizontal - - - QSizePolicy::Expanding - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:6 - - - - - - - - - - - 0 - 0 - - - - - 0 - 160 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 110 - 13 - - - - - + 0 @@ -18895,8 +16247,8 @@ border-radius: 5; - - + + 0 @@ -18906,547 +16258,60 @@ border-radius: 5; 0 - 16 + 22 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - + + + 16777215 + 22 + - - - 75 - true - + + Qt::StrongFocus - - false + + - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; + - - Pitch + + 3 - - Qt::AlignCenter + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Ki + haslimits:no + scale:1 + buttongroup:5,20 + - - + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + 0 @@ -19456,547 +16321,44 @@ border-radius: 5; 0 - 16 + 22 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - + + + 16777215 + 22 + - - - 75 - true - + + Qt::StrongFocus - - false + + - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; + - - Yaw + + 3 - - Qt::AlignCenter + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + - + 0 @@ -20006,72 +16368,22 @@ border-radius: 5; 69 - 30 + 16 - Full stick -angle(deg) + Proportional Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:RollMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - + 0 @@ -20097,69 +16409,25 @@ angle(deg) - 0 - - - 1000000.000000000000000 + 3 - 1.000000000000000 + 0.100000000000000 objname:StabilizationSettings - fieldname:PitchMax + fieldname:PitchPI + element:Kp haslimits:no scale:1 - buttongroup:6,20 + buttongroup:5,20 - - - - - 0 - 0 - - - - - 0 - 30 - - - - - - - Full stick rate -rate(deg/s) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - + + 0 @@ -20188,44 +16456,25 @@ rate(deg/s) - 0 - - - 1000000.000000000000000 + 3 - 1.000000000000000 + 0.100000000000000 objname:StabilizationSettings - fieldname:ManualRate - element:Roll + fieldname:YawPI + element:Ki haslimits:no scale:1 - buttongroup:6,20 + buttongroup:5,20 - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - + 0 @@ -20251,28 +16500,25 @@ rate(deg/s) - 0 - - - 1000000.000000000000000 + 3 - 1.000000000000000 + 0.100000000000000 objname:StabilizationSettings - fieldname:ManualRate - element:Pitch + fieldname:PitchPI + element:Ki haslimits:no scale:1 - buttongroup:6,20 + buttongroup:5,20 - + Qt::Horizontal @@ -20287,8 +16533,8 @@ rate(deg/s) - - + + 0 @@ -20317,266 +16563,2282 @@ rate(deg/s) - 0 - - - 1000000.000000000000000 + 3 - 1.000000000000000 + 0.100000000000000 objname:StabilizationSettings - fieldname:ManualRate - element:Yaw + fieldname:YawPI + element:Kp haslimits:no scale:1 - buttongroup:6,20 + buttongroup:5,20 - - + + 0 0 - - - 125 - 30 - - - - - 16777215 - 16777215 - - - Max rate in attitude - mode(deg/s) + Integral Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Roll - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Pitch - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaximumRate - element:Yaw - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:YawMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + Advanced + + + + 12 + + + 0 + + + + + + + + + + 255 + 255 + 255 + + + + + + + 240 + 240 + 240 + + + + + + + + + 255 + 255 + 255 + + + + + + + 240 + 240 + 240 + + + + + + + + + 240 + 240 + 240 + + + + + + + 240 + 240 + 240 + + + + + + + + QFrame::NoFrame + + + QFrame::Plain + + + true + + + + + 0 + 0 + 962 + 754 + + + + + 0 - 125 + 100 + + + + Axis Lock + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Weak Leveling Kp (deg/s)/deg + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Weak Leveling Rate deg/s + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + + + + 0 + 100 + + + + Weak Leveling + + groupBox_2 + + + + + + + 0 + 150 + + + + ILimits + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 50 + 0 + + + + + 16777215 + 16777215 + + + + + + + ILimit Attitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:ILimit + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 110 + 13 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:ILimit + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:YawPI + element:ILimit + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 50 + 0 + + + + + 16777215 + 16777215 + + + + + + + ILimit Rate Mode + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + + + + + 0 + 0 + + + + + 0 + 150 @@ -21108,7 +19370,7 @@ rate(deg/s) Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - + @@ -23421,6 +21683,66 @@ border-radius: 5; + + + + + 0 + 0 + + + + + 0 + 60 + + + + Real Time Updates + + + + + + + 0 + 0 + + + + + 136 + 20 + + + + If you check this, the GCS will udpate the stabilization factors +automatically every 300ms, which will help for fast tuning. + + + + + + Update in real time + + + + + + + + + + Qt::Vertical + + + + 20 + 149 + + + + @@ -24180,25 +22502,6 @@ Useful if you have accidentally changed some settings. spinBox_19 horizontalSlider_87 spinBox_20 - pushButton_24 - horizontalSlider_88 - spinBox_16 - horizontalSlider_89 - spinBox_17 - horizontalSlider_90 - spinBox_21 - horizontalSlider_91 - spinBox_22 - horizontalSlider_92 - spinBox_23 - horizontalSlider_93 - spinBox_24 - horizontalSlider_94 - spinBox_25 - horizontalSlider_95 - spinBox_26 - horizontalSlider_96 - spinBox_27 stabilizationReloadBoardData_6 saveStabilizationToRAM_6 saveStabilizationToSD_6 @@ -24214,9 +22517,6 @@ Useful if you have accidentally changed some settings. RollRateKd PitchRateKd YawRateKd - RateRollILimit_2 - RatePitchILimit - RateYawILimit checkBox_2 pushButton_2 AttitudeRollKp @@ -24225,9 +22525,6 @@ Useful if you have accidentally changed some settings. AttitudeRollKi AttitudePitchKi_2 AttitudeYawKi - AttitudeRollILimit - AttitudePitchILimit_2 - AttitudeYawILimit pushButton_3 rateRollKp_3 ratePitchKp_4 @@ -24238,10 +22535,6 @@ Useful if you have accidentally changed some settings. rateRollILimit_3 ratePitchILimit_4 rateYawILimit_3 - pushButton_5 - GyroTau - AccelKp - AccelKi From 9ce7d9b4ac35c8f9ae19d5329c5c478a39f13cde Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 29 Jul 2012 15:10:55 -0500 Subject: [PATCH 147/543] Add UAVOs for relay tuning --- flight/Revolution/UAVObjects.inc | 2 ++ .../src/plugins/uavobjects/uavobjects.pro | 4 ++++ shared/uavobjectdefinition/relaytuning.xml | 11 +++++++++++ shared/uavobjectdefinition/relaytuningsettings.xml | 10 ++++++++++ 4 files changed, 27 insertions(+) create mode 100644 shared/uavobjectdefinition/relaytuning.xml create mode 100644 shared/uavobjectdefinition/relaytuningsettings.xml diff --git a/flight/Revolution/UAVObjects.inc b/flight/Revolution/UAVObjects.inc index 462acfc34..bd0612412 100644 --- a/flight/Revolution/UAVObjects.inc +++ b/flight/Revolution/UAVObjects.inc @@ -62,6 +62,8 @@ UAVOBJSRCFILENAMES += overosyncstats UAVOBJSRCFILENAMES += positionactual UAVOBJSRCFILENAMES += positiondesired UAVOBJSRCFILENAMES += ratedesired +UAVOBJSRCFILENAMES += relaytuning +UAVOBJSRCFILENAMES += relaytuningsettings UAVOBJSRCFILENAMES += revocalibration UAVOBJSRCFILENAMES += sonaraltitude UAVOBJSRCFILENAMES += stabilizationdesired diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index 720d36ebd..d252c654a 100755 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -63,6 +63,8 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/velocityactual.h \ $$UAVOBJECT_SYNTHETICS/guidancesettings.h \ $$UAVOBJECT_SYNTHETICS/positiondesired.h \ + $$UAVOBJECT_SYNTHETICS/relaytuning.h \ + $$UAVOBJECT_SYNTHETICS/relaytuningsettings.h \ $$UAVOBJECT_SYNTHETICS/ratedesired.h \ $$UAVOBJECT_SYNTHETICS/firmwareiapobj.h \ $$UAVOBJECT_SYNTHETICS/i2cstats.h \ @@ -125,6 +127,8 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/velocityactual.cpp \ $$UAVOBJECT_SYNTHETICS/guidancesettings.cpp \ $$UAVOBJECT_SYNTHETICS/positiondesired.cpp \ + $$UAVOBJECT_SYNTHETICS/relaytuningsettings.cpp \ + $$UAVOBJECT_SYNTHETICS/relaytuning.cpp \ $$UAVOBJECT_SYNTHETICS/ratedesired.cpp \ $$UAVOBJECT_SYNTHETICS/firmwareiapobj.cpp \ $$UAVOBJECT_SYNTHETICS/i2cstats.cpp \ diff --git a/shared/uavobjectdefinition/relaytuning.xml b/shared/uavobjectdefinition/relaytuning.xml new file mode 100644 index 000000000..f13bfc9f2 --- /dev/null +++ b/shared/uavobjectdefinition/relaytuning.xml @@ -0,0 +1,11 @@ + + + The input to the relay tuning. + + + + + + + + diff --git a/shared/uavobjectdefinition/relaytuningsettings.xml b/shared/uavobjectdefinition/relaytuningsettings.xml new file mode 100644 index 000000000..46a5bc124 --- /dev/null +++ b/shared/uavobjectdefinition/relaytuningsettings.xml @@ -0,0 +1,10 @@ + + + Setting to run a relay tuning algorithm + + + + + + + From 17a0d3ebb41b0a8b5cd0819b5fb10da5ee0336e5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 29 Jul 2012 15:21:14 -0500 Subject: [PATCH 148/543] Add a relay stabilization mode --- flight/Modules/ManualControl/manualcontrol.c | 3 +++ flight/Modules/Stabilization/stabilization.c | 12 ++++++++++++ shared/uavobjectdefinition/manualcontrolsettings.xml | 6 +++--- shared/uavobjectdefinition/stabilizationdesired.xml | 2 +- 4 files changed, 19 insertions(+), 4 deletions(-) diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index cad5d065d..3dc4c53bc 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -589,6 +589,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Roll * stabSettings.RollMax : (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Roll : + (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : 0; // this is an invalid mode ; stabilization.Pitch = (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Pitch : @@ -597,6 +598,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Pitch * stabSettings.PitchMax : (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Pitch : + (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : 0; // this is an invalid mode stabilization.Yaw = (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Yaw : @@ -605,6 +607,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Yaw * stabSettings.YawMax : (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Yaw : + (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : 0; // this is an invalid mode stabilization.Throttle = (cmd->Throttle < 0) ? -1 : cmd->Throttle; diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index 43bb9b0d5..c49f5c103 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -36,6 +36,7 @@ #include "stabilizationsettings.h" #include "actuatordesired.h" #include "ratedesired.h" +#include "relaytuningsettings.h" #include "stabilizationdesired.h" #include "attitudeactual.h" #include "gyros.h" @@ -231,6 +232,7 @@ static void stabilizationTask(void* parameters) { switch(stabDesired.StabilizationMode[i]) { + case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY: case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE: case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR: rateDesiredAxis[i] = attitudeDesiredAxis[i]; @@ -317,6 +319,16 @@ static void stabilizationTask(void* parameters) { switch(stabDesired.StabilizationMode[i]) { + case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY: + { + RelayTuningSettingsData relay; + RelayTuningSettingsGet(&relay); + float error = rateDesiredAxis[i] - gyro_filtered[i]; + float command = error > 0 ? relay.Amplitude : -relay.Amplitude; + actuatorDesiredAxis[i] = bound(command); + break; + break; + } case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE: case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE: case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK: diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index 09d4ca618..8a52b3b23 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -18,9 +18,9 @@ - - - + + + diff --git a/shared/uavobjectdefinition/stabilizationdesired.xml b/shared/uavobjectdefinition/stabilizationdesired.xml index 02c63cd90..f24dd9eeb 100644 --- a/shared/uavobjectdefinition/stabilizationdesired.xml +++ b/shared/uavobjectdefinition/stabilizationdesired.xml @@ -6,7 +6,7 @@ - + From 4ac8df6aa8ca194f31263ef9c6d0a634dfa5c55c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 29 Jul 2012 21:08:46 -0500 Subject: [PATCH 149/543] Make the system perform an online estimate of the period and amplitude of the oscillation during relay tuning --- flight/Modules/Stabilization/stabilization.c | 57 ++++++++++++++++++-- shared/uavobjectdefinition/relaytuning.xml | 3 +- 2 files changed, 55 insertions(+), 5 deletions(-) diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index c49f5c103..3eb2c9c05 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -36,6 +36,7 @@ #include "stabilizationsettings.h" #include "actuatordesired.h" #include "ratedesired.h" +#include "relaytuning.h" #include "relaytuningsettings.h" #include "stabilizationdesired.h" #include "attitudeactual.h" @@ -128,6 +129,8 @@ int32_t StabilizationInitialize() // Initialize variables StabilizationSettingsInitialize(); ActuatorDesiredInitialize(); + RelayTuningSettingsInitialize(); + RelayTuningInitialize(); #if defined(DIAGNOSTICS) RateDesiredInitialize(); #endif @@ -321,12 +324,58 @@ static void stabilizationTask(void* parameters) { case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY: { - RelayTuningSettingsData relay; - RelayTuningSettingsGet(&relay); + RelayTuningSettingsData relaySettings; + RelayTuningSettingsGet(&relaySettings); float error = rateDesiredAxis[i] - gyro_filtered[i]; - float command = error > 0 ? relay.Amplitude : -relay.Amplitude; + float command = error > 0 ? relaySettings.Amplitude : -relaySettings.Amplitude; actuatorDesiredAxis[i] = bound(command); - break; + + RelayTuningData relay; + RelayTuningGet(&relay); + + static bool high = false; + static portTickType lastHighTime; + static portTickType lastLowTime; + portTickType thisTime = xTaskGetTickCount(); + + static float accum_cos, accum_sin; + static uint32_t accumulated = 0; + + const uint16_t DEGLITCH_TIME = 20; // ms + const float AMPLITUDE_ALPHA = 0.95; + const float PERIOD_ALPHA = 0.95; + + // Make sure the period can't go below limit + if (relay.Period[i] < DEGLITCH_TIME) + relay.Period[i] = DEGLITCH_TIME; + + // Project the error onto a sine and cosine of the same frequency + // to accumulate the average amplitude + float dT = thisTime - lastHighTime; + float phase = dT * 2 * M_PI / relay.Period[i]; + accum_cos += cosf(phase) * error; + accum_sin += sinf(phase) * error; + accumulated ++; + + // Make susre we've had enough time since last transition then check for a change in the output + bool hysteresis = (high ? (thisTime - lastHighTime) : (thisTime - lastLowTime)) > DEGLITCH_TIME; + if ( !high && hysteresis && error > 0 ){ /* RISE DETECTED */ + float this_amplitude = 2 * sqrtf(accum_cos*accum_cos + accum_sin*accum_sin) / accumulated; + accumulated = 0; + accum_cos = 0; + accum_sin = 0; + + // Low pass filter each amplitude and period + relay.Amplitude[i] = relay.Amplitude[i] * AMPLITUDE_ALPHA + this_amplitude * (1 - AMPLITUDE_ALPHA); + relay.Period[i] = relay.Period[i] * PERIOD_ALPHA + dT * (1 - PERIOD_ALPHA); + lastHighTime = thisTime; + high = true; + RelayTuningSet(&relay); + } else if ( high && hysteresis && error < 0 ) { /* FALL DETECTED */ + lastLowTime = thisTime; + high = false; + } + break; } case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE: diff --git a/shared/uavobjectdefinition/relaytuning.xml b/shared/uavobjectdefinition/relaytuning.xml index f13bfc9f2..ef54f8b7f 100644 --- a/shared/uavobjectdefinition/relaytuning.xml +++ b/shared/uavobjectdefinition/relaytuning.xml @@ -2,7 +2,8 @@ The input to the relay tuning. - + + From e01c5d5f871a49d94ddf8b6e04df74a47322c087 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 30 Jul 2012 15:20:18 -0500 Subject: [PATCH 150/543] Get online estimation of period and amplitude working --- flight/Modules/Stabilization/stabilization.c | 37 +++++++++++++++----- 1 file changed, 28 insertions(+), 9 deletions(-) diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index 3eb2c9c05..f47aefe9f 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -91,6 +91,9 @@ pid_type pids[PID_MAX]; int8_t vbar_gyros_suppress; bool vbar_piro_comp = false; +// TODO: Move this to flash +static float sin_lookup[360]; + // Private functions static void stabilizationTask(void* parameters); static float ApplyPid(pid_type * pid, const float err, float dT); @@ -107,6 +110,9 @@ int32_t StabilizationStart() // Create object queue queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); + for(uint32_t i = 0; i < 360; i++) + sin_lookup[i] = sinf((float)i * 2 * M_PI / 360.0f); + // Listen for updates. // AttitudeActualConnectQueue(queue); GyrosConnectQueue(queue); @@ -316,6 +322,8 @@ static void stabilizationTask(void* parameters) #if defined(DIAGNOSTICS) RateDesiredSet(&rateDesired); #endif + + static bool rateRelayRunning[3] = {false, false, false}; ActuatorDesiredGet(&actuatorDesired); //Calculate desired command for(uint32_t i = 0; i < MAX_AXES; i++) @@ -338,7 +346,7 @@ static void stabilizationTask(void* parameters) static portTickType lastLowTime; portTickType thisTime = xTaskGetTickCount(); - static float accum_cos, accum_sin; + static float accum_sin, accum_cos; static uint32_t accumulated = 0; const uint16_t DEGLITCH_TIME = 20; // ms @@ -352,22 +360,30 @@ static void stabilizationTask(void* parameters) // Project the error onto a sine and cosine of the same frequency // to accumulate the average amplitude float dT = thisTime - lastHighTime; - float phase = dT * 2 * M_PI / relay.Period[i]; - accum_cos += cosf(phase) * error; - accum_sin += sinf(phase) * error; + uint32_t phase = 360 * dT / relay.Period[i]; + if(phase >= 360) + phase = 1; + accum_sin += sin_lookup[phase] * error; + accum_cos += sin_lookup[(phase + 90) % 360] * error; accumulated ++; // Make susre we've had enough time since last transition then check for a change in the output bool hysteresis = (high ? (thisTime - lastHighTime) : (thisTime - lastLowTime)) > DEGLITCH_TIME; if ( !high && hysteresis && error > 0 ){ /* RISE DETECTED */ - float this_amplitude = 2 * sqrtf(accum_cos*accum_cos + accum_sin*accum_sin) / accumulated; + float this_amplitude = 2 * sqrtf(accum_sin*accum_sin + accum_cos*accum_cos) / accumulated; accumulated = 0; - accum_cos = 0; accum_sin = 0; + accum_cos = 0; - // Low pass filter each amplitude and period - relay.Amplitude[i] = relay.Amplitude[i] * AMPLITUDE_ALPHA + this_amplitude * (1 - AMPLITUDE_ALPHA); - relay.Period[i] = relay.Period[i] * PERIOD_ALPHA + dT * (1 - PERIOD_ALPHA); + if(rateRelayRunning[i] == false) { + rateRelayRunning[i] = true; + relay.Period[i] = 200; + relay.Amplitude[i] = 0; + } else { + // Low pass filter each amplitude and period + relay.Amplitude[i] = relay.Amplitude[i] * AMPLITUDE_ALPHA + this_amplitude * (1 - AMPLITUDE_ALPHA); + relay.Period[i] = relay.Period[i] * PERIOD_ALPHA + dT * (1 - PERIOD_ALPHA); + } lastHighTime = thisTime; high = true; RelayTuningSet(&relay); @@ -383,12 +399,14 @@ static void stabilizationTask(void* parameters) case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK: case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING: { + rateRelayRunning[i] = false; float command = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); actuatorDesiredAxis[i] = bound(command); break; } case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR: { + rateRelayRunning[i] = false; // Track the angle of the virtual flybar which includes a slow decay vbar_integral[i] = vbar_integral[i] * vbar_decay + gyro_filtered[i] * dT; if (vbar_integral[i] > settings.VbarMaxAngle) @@ -410,6 +428,7 @@ static void stabilizationTask(void* parameters) break; } case STABILIZATIONDESIRED_STABILIZATIONMODE_NONE: + rateRelayRunning[i] = false; switch (i) { case ROLL: From 44e72d0a700bda4fe5f5d0cd2a064d83ca9e8900 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 30 Jul 2012 20:55:43 -0500 Subject: [PATCH 151/543] A big refactoring of stabilization.c to get rid of the two separate loops and move them into one big structure. This makes it easier to implement other modes. --- flight/Modules/Stabilization/stabilization.c | 454 +++++++++++-------- 1 file changed, 273 insertions(+), 181 deletions(-) diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index f47aefe9f..87bee87cd 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -97,7 +97,7 @@ static float sin_lookup[360]; // Private functions static void stabilizationTask(void* parameters); static float ApplyPid(pid_type * pid, const float err, float dT); -static float bound(float val); +static float bound(float val, float range); static void ZeroPids(void); static void SettingsUpdatedCb(UAVObjEvent * ev); @@ -116,10 +116,10 @@ int32_t StabilizationStart() // Listen for updates. // AttitudeActualConnectQueue(queue); GyrosConnectQueue(queue); - + StabilizationSettingsConnectCallback(SettingsUpdatedCb); SettingsUpdatedCb(StabilizationSettingsHandle()); - + // Start main task xTaskCreate(stabilizationTask, (signed char*)"Stabilization", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); TaskMonitorAdd(TASKINFO_RUNNING_STABILIZATION, taskHandle); @@ -140,7 +140,7 @@ int32_t StabilizationInitialize() #if defined(DIAGNOSTICS) RateDesiredInitialize(); #endif - + return 0; } @@ -152,73 +152,73 @@ MODULE_INITCALL(StabilizationInitialize, StabilizationStart) static void stabilizationTask(void* parameters) { UAVObjEvent ev; - + uint32_t timeval = PIOS_DELAY_GetRaw(); - + ActuatorDesiredData actuatorDesired; StabilizationDesiredData stabDesired; RateDesiredData rateDesired; AttitudeActualData attitudeActual; GyrosData gyrosData; FlightStatusData flightStatus; - + SettingsUpdatedCb((UAVObjEvent *) NULL); - + // Main task loop ZeroPids(); while(1) { float dT; - + PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION); - + // Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe if ( xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE ) { AlarmsSet(SYSTEMALARMS_ALARM_STABILIZATION,SYSTEMALARMS_ALARM_WARNING); continue; } - + dT = PIOS_DELAY_DiffuS(timeval) * 1.0e-6f; timeval = PIOS_DELAY_GetRaw(); - + FlightStatusGet(&flightStatus); StabilizationDesiredGet(&stabDesired); AttitudeActualGet(&attitudeActual); GyrosGet(&gyrosData); - + #if defined(DIAGNOSTICS) RateDesiredGet(&rateDesired); #endif - + #if defined(PIOS_QUATERNION_STABILIZATION) // Quaternion calculation of error in each axis. Uses more memory. float rpy_desired[3]; float q_desired[4]; float q_error[4]; float local_error[3]; - + // Essentially zero errors for anything in rate or none if(stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) rpy_desired[0] = stabDesired.Roll; else rpy_desired[0] = attitudeActual.Roll; - + if(stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) rpy_desired[1] = stabDesired.Pitch; else rpy_desired[1] = attitudeActual.Pitch; - + if(stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) rpy_desired[2] = stabDesired.Yaw; else rpy_desired[2] = attitudeActual.Yaw; - + RPY2Quaternion(rpy_desired, q_desired); quat_inverse(q_desired); quat_mult(q_desired, &attitudeActual.q1, q_error); quat_inverse(q_error); Quaternion2RPY(q_error, local_error); - + #else // Simpler algorithm for CC, less memory float local_error[3] = {stabDesired.Roll - attitudeActual.Roll, @@ -227,7 +227,6 @@ static void stabilizationTask(void* parameters) local_error[2] = fmodf(local_error[2] + 180, 360) - 180; #endif - gyro_filtered[0] = gyro_filtered[0] * gyro_alpha + gyrosData.x * (1 - gyro_alpha); gyro_filtered[1] = gyro_filtered[1] * gyro_alpha + gyrosData.y * (1 - gyro_alpha); gyro_filtered[2] = gyro_filtered[2] * gyro_alpha + gyrosData.z * (1 - gyro_alpha); @@ -236,50 +235,98 @@ static void stabilizationTask(void* parameters) float *actuatorDesiredAxis = &actuatorDesired.Roll; float *rateDesiredAxis = &rateDesired.Roll; - //Calculate desired rate + ActuatorDesiredGet(&actuatorDesired); + + // A flag to track which stabilization mode each axis is in + static uint8_t previous_mode[MAX_AXES] = {255,255,255}; + bool error = false; + + //Run the selected stabilization algorithm on each axis: for(uint8_t i=0; i< MAX_AXES; i++) { + // Check whether this axis mode needs to be reinitialized + bool reinit = (stabDesired.StabilizationMode[i] == previous_mode[i]); + previous_mode[i] = stabDesired.StabilizationMode[i]; + + // Apply the selected control law switch(stabDesired.StabilizationMode[i]) { - case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY: case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE: + if(reinit) + pids[PID_RATE_ROLL + i].iAccumulator = 0; + + // Store to rate desired variable for storing to UAVO + rateDesiredAxis[i] = bound(attitudeDesiredAxis[i], settings.ManualRate[i]); + + // Compute the inner loop + actuatorDesiredAxis[i] = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); + actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0f); + + break; + + case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE: + if(reinit) { + pids[PID_ROLL + i].iAccumulator = 0; + pids[PID_RATE_ROLL + i].iAccumulator = 0; + } + + // Compute the outer loop + rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i], dT); + rateDesiredAxis[i] = bound(rateDesiredAxis[i], settings.MaximumRate[i]); + + // Compute the inner loop + actuatorDesiredAxis[i] = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); + actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0f); + + break; + case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR: + { + if(reinit) + vbar_integral[i] = 0; + rateDesiredAxis[i] = attitudeDesiredAxis[i]; - // Zero attitude and axis lock accumulators - pids[PID_ROLL + i].iAccumulator = 0; - axis_lock_accum[i] = 0; - break; + // Track the angle of the virtual flybar which includes a slow decay + vbar_integral[i] = vbar_integral[i] * vbar_decay + gyro_filtered[i] * dT; + vbar_integral[i] = bound(vbar_integral[i], settings.VbarMaxAngle); - case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING: - { - float weak_leveling = local_error[i] * weak_leveling_kp; + // Command signal can indicate how much to disregard the gyro feedback (fast flips) + float gyro_gain = 1.0f; + if (vbar_gyros_suppress > 0) { + gyro_gain = (1.0f - fabs(rateDesiredAxis[i]) * vbar_gyros_suppress / 100.0f); + gyro_gain = (gyro_gain < 0) ? 0 : gyro_gain; + } - if(weak_leveling > weak_leveling_max) - weak_leveling = weak_leveling_max; - if(weak_leveling < -weak_leveling_max) - weak_leveling = -weak_leveling_max; + // Command signal is composed of stick input added to the gyro and virtual flybar + actuatorDesiredAxis[i] = rateDesiredAxis[i] * vbar_sensitivity[i] - + gyro_gain * (vbar_integral[i] * pids[PID_VBAR_ROLL + i].i + + gyro_filtered[i] * pids[PID_VBAR_ROLL + i].p); - rateDesiredAxis[i] = attitudeDesiredAxis[i] + weak_leveling; + actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0f); - // Zero attitude and axis lock accumulators - pids[PID_ROLL + i].iAccumulator = 0; - axis_lock_accum[i] = 0; break; } - case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE: - rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i], dT); - - if(rateDesiredAxis[i] > settings.MaximumRate[i]) - rateDesiredAxis[i] = settings.MaximumRate[i]; - else if(rateDesiredAxis[i] < -settings.MaximumRate[i]) - rateDesiredAxis[i] = -settings.MaximumRate[i]; - - - axis_lock_accum[i] = 0; + case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING: + { + if (reinit) + pids[PID_RATE_ROLL + i].iAccumulator = 0; + + float weak_leveling = local_error[i] * weak_leveling_kp; + weak_leveling = bound(weak_leveling, weak_leveling_max); + + // Compute desired rate as input biased towards leveling + rateDesiredAxis[i] = attitudeDesiredAxis[i] + weak_leveling; + actuatorDesiredAxis[i] = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); + actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0f); + break; + } case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK: + if (reinit) + pids[PID_RATE_ROLL + i].iAccumulator = 0; + if(fabs(attitudeDesiredAxis[i]) > max_axislock_rate) { // While getting strong commands act like rate mode rateDesiredAxis[i] = attitudeDesiredAxis[i]; @@ -287,59 +334,46 @@ static void stabilizationTask(void* parameters) } else { // For weaker commands or no command simply attitude lock (almost) on no gyro change axis_lock_accum[i] += (attitudeDesiredAxis[i] - gyro_filtered[i]) * dT; - if(axis_lock_accum[i] > max_axis_lock) - axis_lock_accum[i] = max_axis_lock; - else if(axis_lock_accum[i] < -max_axis_lock) - axis_lock_accum[i] = -max_axis_lock; - + axis_lock_accum[i] = bound(axis_lock_accum[i], max_axis_lock); rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], axis_lock_accum[i], dT); } - - if(rateDesiredAxis[i] > settings.MaximumRate[i]) - rateDesiredAxis[i] = settings.MaximumRate[i]; - else if(rateDesiredAxis[i] < -settings.MaximumRate[i]) - rateDesiredAxis[i] = -settings.MaximumRate[i]; + + rateDesiredAxis[i] = bound(rateDesiredAxis[i], settings.MaximumRate[i]); + + actuatorDesiredAxis[i] = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); + actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0f); break; - } - } - // Piro compensation rotates the virtual flybar by yaw step to keep it - // rotated to external world - if (vbar_piro_comp) { - const float F_PI = 3.14159f; - float cy = cosf(gyro_filtered[2] / 180.0f * F_PI * dT); - float sy = sinf(gyro_filtered[2] / 180.0f * F_PI * dT); - - float vbar_pitch = cy * vbar_integral[1] - sy * vbar_integral[0]; - float vbar_roll = sy * vbar_integral[1] + cy * vbar_integral[0]; - - vbar_integral[1] = vbar_pitch; - vbar_integral[0] = vbar_roll; - } - - uint8_t shouldUpdate = 1; -#if defined(DIAGNOSTICS) - RateDesiredSet(&rateDesired); -#endif - - static bool rateRelayRunning[3] = {false, false, false}; - ActuatorDesiredGet(&actuatorDesired); - //Calculate desired command - for(uint32_t i = 0; i < MAX_AXES; i++) - { - switch(stabDesired.StabilizationMode[i]) - { - case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY: + case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE: { + RelayTuningData relay; + RelayTuningGet(&relay); + + static bool rateRelayRunning[MAX_AXES]; + + // On first run initialize estimates to something reasonable + if(reinit) { + pids[PID_ROLL + i].iAccumulator = 0; + rateRelayRunning[i] = false; + relay.Period[i] = 200; + relay.Gain[i] = 0; + } + // Replace the rate PID with a relay to measure the critical properties of this axis + // i.e. period and gain + + // Compute the outer loop + rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i], dT); + rateDesiredAxis[i] = bound(rateDesiredAxis[i], settings.MaximumRate[i]); + + // Store to rate desired variable for storing to UAVO + rateDesiredAxis[i] = bound(attitudeDesiredAxis[i], settings.ManualRate[i]); + RelayTuningSettingsData relaySettings; RelayTuningSettingsGet(&relaySettings); float error = rateDesiredAxis[i] - gyro_filtered[i]; float command = error > 0 ? relaySettings.Amplitude : -relaySettings.Amplitude; - actuatorDesiredAxis[i] = bound(command); - - RelayTuningData relay; - RelayTuningGet(&relay); + actuatorDesiredAxis[i] = bound(command,1.0f); static bool high = false; static portTickType lastHighTime; @@ -371,6 +405,8 @@ static void stabilizationTask(void* parameters) bool hysteresis = (high ? (thisTime - lastHighTime) : (thisTime - lastLowTime)) > DEGLITCH_TIME; if ( !high && hysteresis && error > 0 ){ /* RISE DETECTED */ float this_amplitude = 2 * sqrtf(accum_sin*accum_sin + accum_cos*accum_cos) / accumulated; + float this_gain = this_amplitude / relaySettings.Amplitude; + accumulated = 0; accum_sin = 0; accum_cos = 0; @@ -378,10 +414,10 @@ static void stabilizationTask(void* parameters) if(rateRelayRunning[i] == false) { rateRelayRunning[i] = true; relay.Period[i] = 200; - relay.Amplitude[i] = 0; + relay.Gain[i] = 0; } else { // Low pass filter each amplitude and period - relay.Amplitude[i] = relay.Amplitude[i] * AMPLITUDE_ALPHA + this_amplitude * (1 - AMPLITUDE_ALPHA); + relay.Gain[i] = relay.Gain[i] * AMPLITUDE_ALPHA + this_gain * (1 - AMPLITUDE_ALPHA); relay.Period[i] = relay.Period[i] * PERIOD_ALPHA + dT * (1 - PERIOD_ALPHA); } lastHighTime = thisTime; @@ -394,110 +430,165 @@ static void stabilizationTask(void* parameters) break; } - case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE: - case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE: - case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK: - case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING: + case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE: { - rateRelayRunning[i] = false; - float command = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); - actuatorDesiredAxis[i] = bound(command); - break; - } - case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR: - { - rateRelayRunning[i] = false; - // Track the angle of the virtual flybar which includes a slow decay - vbar_integral[i] = vbar_integral[i] * vbar_decay + gyro_filtered[i] * dT; - if (vbar_integral[i] > settings.VbarMaxAngle) - vbar_integral[i] = settings.VbarMaxAngle; - if (-vbar_integral[i] < -settings.VbarMaxAngle) - vbar_integral[i] = -settings.VbarMaxAngle; + RelayTuningData relay; + RelayTuningGet(&relay); - // Command signal is composed of stick input added to the gyro and virtual flybar - float gyro_gain = 1.0f; - if (vbar_gyros_suppress > 0) { - gyro_gain = (1.0f - fabs(rateDesiredAxis[i]) * vbar_gyros_suppress / 100.0f); - gyro_gain = (gyro_gain < 0) ? 0 : gyro_gain; + static bool rateRelayRunning[MAX_AXES]; + + // On first run initialize estimates to something reasonable + if(reinit) { + pids[PID_ROLL + i].iAccumulator = 0; + rateRelayRunning[i] = false; + relay.Period[i] = 200; + relay.Gain[i] = 0; } - float command = rateDesiredAxis[i] * vbar_sensitivity[i] - gyro_gain * ( - vbar_integral[i] * pids[PID_VBAR_ROLL + i].i + - gyro_filtered[i] * pids[PID_VBAR_ROLL + i].p); - actuatorDesiredAxis[i] = bound(command); - break; + // Replace the rate PID with a relay to measure the critical properties of this axis + // i.e. period and gain + + // Store to rate desired variable for storing to UAVO + rateDesiredAxis[i] = bound(attitudeDesiredAxis[i], settings.ManualRate[i]); + + RelayTuningSettingsData relaySettings; + RelayTuningSettingsGet(&relaySettings); + float error = rateDesiredAxis[i] - gyro_filtered[i]; + float command = error > 0 ? relaySettings.Amplitude : -relaySettings.Amplitude; + actuatorDesiredAxis[i] = bound(command,1.0); + + static bool high = false; + static portTickType lastHighTime; + static portTickType lastLowTime; + portTickType thisTime = xTaskGetTickCount(); + + static float accum_sin, accum_cos; + static uint32_t accumulated = 0; + + const uint16_t DEGLITCH_TIME = 20; // ms + const float AMPLITUDE_ALPHA = 0.95; + const float PERIOD_ALPHA = 0.95; + + // Make sure the period can't go below limit + if (relay.Period[i] < DEGLITCH_TIME) + relay.Period[i] = DEGLITCH_TIME; + + // Project the error onto a sine and cosine of the same frequency + // to accumulate the average amplitude + float dT = thisTime - lastHighTime; + uint32_t phase = 360 * dT / relay.Period[i]; + if(phase >= 360) + phase = 1; + accum_sin += sin_lookup[phase] * error; + accum_cos += sin_lookup[(phase + 90) % 360] * error; + accumulated ++; + + // Make susre we've had enough time since last transition then check for a change in the output + bool hysteresis = (high ? (thisTime - lastHighTime) : (thisTime - lastLowTime)) > DEGLITCH_TIME; + if ( !high && hysteresis && error > 0 ){ /* RISE DETECTED */ + float this_amplitude = 2 * sqrtf(accum_sin*accum_sin + accum_cos*accum_cos) / accumulated; + float this_gain = this_amplitude / relaySettings.Amplitude; + + accumulated = 0; + accum_sin = 0; + accum_cos = 0; + + if(rateRelayRunning[i] == false) { + rateRelayRunning[i] = true; + relay.Period[i] = 200; + relay.Gain[i] = 0; + } else { + // Low pass filter each amplitude and period + relay.Gain[i] = relay.Gain[i] * AMPLITUDE_ALPHA + this_gain * (1 - AMPLITUDE_ALPHA); + relay.Period[i] = relay.Period[i] * PERIOD_ALPHA + dT * (1 - PERIOD_ALPHA); + } + lastHighTime = thisTime; + high = true; + RelayTuningSet(&relay); + } else if ( high && hysteresis && error < 0 ) { /* FALL DETECTED */ + lastLowTime = thisTime; + high = false; + } } + break; + case STABILIZATIONDESIRED_STABILIZATIONMODE_NONE: - rateRelayRunning[i] = false; - switch (i) - { - case ROLL: - actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i]); - shouldUpdate = 1; - pids[PID_RATE_ROLL].iAccumulator = 0; - pids[PID_ROLL].iAccumulator = 0; - break; - case PITCH: - actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i]); - shouldUpdate = 1; - pids[PID_RATE_PITCH].iAccumulator = 0; - pids[PID_PITCH].iAccumulator = 0; - break; - case YAW: - actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i]); - shouldUpdate = 1; - pids[PID_RATE_YAW].iAccumulator = 0; - pids[PID_YAW].iAccumulator = 0; - break; - } + actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i],1.0f); + break; + default: + error = true; break; - } } + // Piro compensation rotates the virtual flybar by yaw step to keep it + // rotated to external world + if (vbar_piro_comp) { + const float F_PI = 3.14159f; + float cy = cosf(gyro_filtered[2] / 180.0f * F_PI * dT); + float sy = sinf(gyro_filtered[2] / 180.0f * F_PI * dT); + + float vbar_pitch = cy * vbar_integral[1] - sy * vbar_integral[0]; + float vbar_roll = sy * vbar_integral[1] + cy * vbar_integral[0]; + + vbar_integral[1] = vbar_pitch; + vbar_integral[0] = vbar_roll; + } + +#if defined(DIAGNOSTICS) + RateDesiredSet(&rateDesired); +#endif + // Save dT actuatorDesired.UpdateTime = dT * 1000; + actuatorDesired.Throttle = stabDesired.Throttle; - if(PARSE_FLIGHT_MODE(flightStatus.FlightMode) == FLIGHTMODE_MANUAL) - shouldUpdate = 0; - - if(shouldUpdate) - { - actuatorDesired.Throttle = stabDesired.Throttle; - if(dT > 15) - actuatorDesired.NumLongUpdates++; + if(PARSE_FLIGHT_MODE(flightStatus.FlightMode) != FLIGHTMODE_MANUAL) { ActuatorDesiredSet(&actuatorDesired); + } else { + // Force all axes to reinitialize when engaged + for(uint8_t i=0; i< MAX_AXES; i++) + previous_mode[i] = 255; } if(flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED || - (lowThrottleZeroIntegral && stabDesired.Throttle < 0) || - !shouldUpdate) + (lowThrottleZeroIntegral && stabDesired.Throttle < 0)) { - ZeroPids(); + // Force all axes to reinitialize when engaged + for(uint8_t i=0; i< MAX_AXES; i++) + previous_mode[i] = 255; } - - // Clear alarms - AlarmsClear(SYSTEMALARMS_ALARM_STABILIZATION); + // Clear or set alarms. Done like this to prevent toggline each cycle + // and hammering system alarms + if (error) + AlarmsSet(SYSTEMALARMS_ALARM_STABILIZATION,SYSTEMALARMS_ALARM_ERROR); + else + AlarmsClear(SYSTEMALARMS_ALARM_STABILIZATION); } } +/** + * Update one of the PID structures with the input error and timestep + * @param pid Pointer to the PID structure + * @param[in] err The error on for this controller + * @param[in] dT The time step since the last update + */ float ApplyPid(pid_type * pid, const float err, float dT) { float diff = (err - pid->lastErr); pid->lastErr = err; - + // Scale up accumulator by 1000 while computing to avoid losing precision pid->iAccumulator += err * (pid->i * dT * 1000.0f); - if(pid->iAccumulator > (pid->iLim * 1000.0f)) { - pid->iAccumulator = pid->iLim * 1000.0f; - } else if (pid->iAccumulator < -(pid->iLim * 1000.0f)) { - pid->iAccumulator = -pid->iLim * 1000.0f; - } + pid->iAccumulator = bound(pid->iAccumulator, pid->iLim * 1000.0f); return ((err * pid->p) + pid->iAccumulator / 1000.0f + (diff * pid->d / dT)); } +/** + * Clear the accumulators and derivatives for all the axes + */ static void ZeroPids(void) { for(int8_t ct = 0; ct < PID_MAX; ct++) { @@ -512,12 +603,12 @@ static void ZeroPids(void) /** * Bound input value between limits */ -static float bound(float val) +static float bound(float val, float range) { - if(val < -1.0f) { - val = -1.0f; - } else if(val > 1.0f) { - val = 1.0f; + if(val < -range) { + val = -range; + } else if(val > range) { + val = range; } return val; } @@ -525,40 +616,40 @@ static float bound(float val) static void SettingsUpdatedCb(UAVObjEvent * ev) { StabilizationSettingsGet(&settings); - + // Set the roll rate PID constants pids[PID_RATE_ROLL].p = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP]; pids[PID_RATE_ROLL].i = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI]; pids[PID_RATE_ROLL].d = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD]; pids[PID_RATE_ROLL].iLim = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT]; - + // Set the pitch rate PID constants pids[PID_RATE_PITCH].p = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP]; pids[PID_RATE_PITCH].i = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI]; pids[PID_RATE_PITCH].d = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD]; pids[PID_RATE_PITCH].iLim = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT]; - + // Set the yaw rate PID constants pids[PID_RATE_YAW].p = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP]; pids[PID_RATE_YAW].i = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI]; pids[PID_RATE_YAW].d = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD]; pids[PID_RATE_YAW].iLim = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT]; - + // Set the roll attitude PI constants pids[PID_ROLL].p = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP]; pids[PID_ROLL].i = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI]; pids[PID_ROLL].iLim = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT]; - + // Set the pitch attitude PI constants pids[PID_PITCH].p = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP]; pids[PID_PITCH].i = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI]; pids[PID_PITCH].iLim = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT]; - + // Set the yaw attitude PI constants pids[PID_YAW].p = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KP]; pids[PID_YAW].i = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KI]; pids[PID_YAW].iLim = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT]; - + // Set the roll attitude PI constants pids[PID_VBAR_ROLL].p = settings.VbarRollPI[STABILIZATIONSETTINGS_VBARROLLPI_KP]; pids[PID_VBAR_ROLL].i = settings.VbarRollPI[STABILIZATIONSETTINGS_VBARROLLPI_KI]; @@ -570,23 +661,23 @@ static void SettingsUpdatedCb(UAVObjEvent * ev) // Set the yaw attitude PI constants pids[PID_VBAR_YAW].p = settings.VbarYawPI[STABILIZATIONSETTINGS_VBARYAWPI_KP]; pids[PID_VBAR_YAW].i = settings.VbarYawPI[STABILIZATIONSETTINGS_VBARYAWPI_KI]; - + // Need to store the vbar sensitivity vbar_sensitivity[0] = settings.VbarSensitivity[0]; vbar_sensitivity[1] = settings.VbarSensitivity[1]; vbar_sensitivity[2] = settings.VbarSensitivity[2]; - + // Maximum deviation to accumulate for axis lock max_axis_lock = settings.MaxAxisLock; max_axislock_rate = settings.MaxAxisLockRate; - + // Settings for weak leveling weak_leveling_kp = settings.WeakLevelingKp; weak_leveling_max = settings.MaxWeakLevelingRate; - + // Whether to zero the PID integrals while throttle is low lowThrottleZeroIntegral = settings.LowThrottleZeroIntegral == STABILIZATIONSETTINGS_LOWTHROTTLEZEROINTEGRAL_TRUE; - + // The dT has some jitter iteration to iteration that we don't want to // make thie result unpredictable. Still, it's nicer to specify the constant // based on a time (in ms) rather than a fixed multiplier. The error between @@ -597,7 +688,7 @@ static void SettingsUpdatedCb(UAVObjEvent * ev) gyro_alpha = 0; // not trusting this to resolve to 0 else gyro_alpha = expf(-fakeDt / settings.GyroTau); - + // Compute time constant for vbar decay term based on a tau vbar_decay = expf(-fakeDt / settings.VbarTau); vbar_gyros_suppress = settings.VbarGyroSuppress; @@ -609,3 +700,4 @@ static void SettingsUpdatedCb(UAVObjEvent * ev) * @} * @} */ + From a9af53b4f364fcad455e61570eca7be0f0de21f3 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 31 Jul 2012 02:04:36 -0500 Subject: [PATCH 152/543] Create new autotuning module which rotates through the axes for autotuning and then computes new stabilization settings. --- flight/Modules/Autotune/autotune.c | 291 ++++++++++++++++++ flight/Modules/Autotune/inc/autotune.h | 37 +++ shared/uavobjectdefinition/flightstatus.xml | 2 +- .../manualcontrolsettings.xml | 2 +- 4 files changed, 330 insertions(+), 2 deletions(-) create mode 100644 flight/Modules/Autotune/autotune.c create mode 100644 flight/Modules/Autotune/inc/autotune.h diff --git a/flight/Modules/Autotune/autotune.c b/flight/Modules/Autotune/autotune.c new file mode 100644 index 000000000..3fc9246e4 --- /dev/null +++ b/flight/Modules/Autotune/autotune.c @@ -0,0 +1,291 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup Autotuning module + * @brief Reads from @ref ManualControlCommand and fakes a rate mode while + * toggling the channels to relay mode + * @{ + * + * @file autotune.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Module to handle all comms to the AHRS on a periodic basis. + * + * @see The GNU Public License (GPL) Version 3 + * + ******************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/** + * Input objects: None, takes sensor data via pios + * Output objects: @ref AttitudeRaw @ref AttitudeActual + * + * This module computes an attitude estimate from the sensor data + * + * The module executes in its own thread. + * + * UAVObjects are automatically generated by the UAVObjectGenerator from + * the object definition XML file. + * + * Modules have no API, all communication to other modules is done through UAVObjects. + * However modules may use the API exposed by shared libraries. + * See the OpenPilot wiki for more details. + * http://www.openpilot.org/OpenPilot_Application_Architecture + * + */ + +#include "pios.h" +#include "flightstatus.h" +#include "manualcontrolcommand.h" +#include "manualcontrolsettings.h" +#include "relaytuning.h" +#include "relaytuningsettings.h" +#include "stabilizationdesired.h" +#include "stabilizationsettings.h" +#include + +// Private constants +#define STACK_SIZE_BYTES 1024 +#define TASK_PRIORITY (tskIDLE_PRIORITY+2) + +// Private types +enum AUTOTUNE_STATE {AT_INIT, AT_START, AT_ROLL, AT_PITCH, AT_FINISHED, AT_SET}; + +// Private variables +static xTaskHandle taskHandle; + +// Private functions +static void AutotuneTask(void *parameters); +static void update_stabilization_settings(); + +/** + * Initialise the module, called on startup + * \returns 0 on success or -1 if initialisation failed + */ +int32_t AutotuneInitialize(void) +{ + // Create a queue, connect to manual control command and flightstatus + + return 0; +} + +/** + * Initialise the module, called on startup + * \returns 0 on success or -1 if initialisation failed + */ +int32_t AutotuneStart(void) +{ + + // Start main task + xTaskCreate(AutotuneTask, (signed char *)"Autotune", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); + + //TaskMonitorAdd(TASKINFO_RUNNING_ATTITUDE, taskHandle); + //PIOS_WDG_RegisterFlag(PIOS_WDG_ATTITUDE); + + return 0; +} + +MODULE_INITCALL(AutotuneInitialize, AutotuneStart) + +/** + * Module thread, should not return. + */ +static void AutotuneTask(void *parameters) +{ + //AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); + + enum AUTOTUNE_STATE state = AT_INIT; + + portTickType lastUpdateTime = xTaskGetTickCount(); + + while(1) { + // TODO: + // 1. get from queue + // 2. based on whether it is flightstatus or manualcontrol + + portTickType diffTime; + + const uint32_t PREPARE_TIME = 2000; + const uint32_t MEAURE_TIME = 10000; + + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + + // Only allow this module to run when autotuning + if (flightStatus.FlightMode != FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE) { + state = AT_INIT; + vTaskDelay(50); + continue; + } + + StabilizationDesiredData stabDesired; + StabilizationDesiredGet(&stabDesired); + + StabilizationSettingsData stabSettings; + StabilizationSettingsGet(&stabSettings); + + ManualControlSettingsData manualSettings; + ManualControlSettingsGet(&manualSettings); + + ManualControlCommandData manualControl; + ManualControlCommandGet(&manualControl); + + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; + + stabDesired.Roll = manualControl.Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL]; + stabDesired.Pitch = manualControl.Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH]; + stabDesired.Yaw = manualControl.Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW]; + stabDesired.Throttle = manualControl.Throttle; + + switch(state) { + case AT_INIT: + + lastUpdateTime = xTaskGetTickCount(); + + // Only start when armed and flying + if (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED && stabDesired.Throttle > 0) + state = AT_START; + break; + + case AT_START: + + diffTime = xTaskGetTickCount() - lastUpdateTime; + + // Spend the first block of time in normal rate mode to get airborne + if (diffTime > PREPARE_TIME) { + state = AT_ROLL; + lastUpdateTime = xTaskGetTickCount(); + } + break; + + case AT_ROLL: + + diffTime = xTaskGetTickCount() - lastUpdateTime; + + // Run relay mode on the roll axis for the measurement time + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY; + if (diffTime > MEAURE_TIME) { // Move on to next state + state = AT_PITCH; + lastUpdateTime = xTaskGetTickCount(); + } + break; + + case AT_PITCH: + + diffTime = xTaskGetTickCount() - lastUpdateTime; + + // Run relay mode on the pitch axis for the measurement time + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY; + if (diffTime > MEAURE_TIME) { // Move on to next state + state = AT_FINISHED; + lastUpdateTime = xTaskGetTickCount(); + } + break; + + case AT_FINISHED: + + // Wait until disarmed and landed before updating the settings + if (flightStatus.Armed == FLIGHTSTATUS_ARMED_DISARMED && stabDesired.Throttle <= 0) + state = AT_SET; + + break; + + case AT_SET: + update_stabilization_settings(); + state = AT_INIT; + break; + + default: + // Set an alarm or some shit like that + break; + } + + StabilizationDesiredSet(&stabDesired); + + vTaskDelay(10); + } +} + +/** + * Called after measuring roll and pitch to update the + * stabilization settings + * + * takes in @ref RelayTuning and outputs @ref StabilizationSettings + */ +static void update_stabilization_settings() +{ + RelayTuningData relayTuning; + RelayTuningGet(&relayTuning); + + RelayTuningSettingsData relaySettings; + RelayTuningSettingsGet(&relaySettings); + + StabilizationSettingsData stabSettings; + StabilizationSettingsGet(&stabSettings); + + // Eventually get these settings from RelayTuningSettings + const float gain_ratio_r = 1.0f / 3.0f; + const float zero_ratio_r = 1.0f / 3.0f; + const float gain_ratio_p = 1.0f / 5.0f; + const float zero_ratio_p = 1.0f / 5.0f; + + float input = relaySettings.Amplitude * 4.0f / M_PI; // amplitude of input (fundamental component of fourier series for the square wave) + + // For now just run over roll and pitch + for (uint i = 0; i < 2; i++) { + float output = relayTuning.Amplitude[i]; // amplitude of sinusoidal oscillation in output + float wu = 1000.0f * 2 * M_PI / relayTuning.Period[i]; // ultimate freq = output osc freq (rad/s) + + float wc = wu * gain_ratio_r; // target openloop crossover frequency (rad/s) + float zc = wc * zero_ratio_r; // controller zero location (rad/s) + float kpu = input / output; // ultimate gain, i.e. the proportional gain for instablity + float kp = kpu * gain_ratio_r; // proportional gain + float ki = zc * kp; // integral gain + + // Now calculate gains for the next loop out knowing it is the integral of + // the inner loop -- the plant is position/velocity = scale*1/s + float wc2 = wc * gain_ratio_p; // crossover of the attitude loop + float kp2 = wc2; // kp of attitude + float ki2 = wc2 * zero_ratio_p * kp2; // ki of attitude + + switch(i) { + case 0: // roll + stabSettings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP] = kp; + stabSettings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI] = ki; + stabSettings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP] = kp2; + stabSettings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI] = ki2; + break; + case 1: // Pitch + stabSettings.PitchRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP] = kp; + stabSettings.PitchRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI] = ki; + stabSettings.PitchPI[STABILIZATIONSETTINGS_ROLLPI_KP] = kp2; + stabSettings.PitchPI[STABILIZATIONSETTINGS_ROLLPI_KI] = ki2; + break; + default: + // Oh shit oh shit oh shit + break; + } + } + StabilizationSettingsSet(&stabSettings); +} + +/** + * @} + * @} + */ diff --git a/flight/Modules/Autotune/inc/autotune.h b/flight/Modules/Autotune/inc/autotune.h new file mode 100644 index 000000000..3f90e56a6 --- /dev/null +++ b/flight/Modules/Autotune/inc/autotune.h @@ -0,0 +1,37 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup Attitude Attitude Module + * @{ + * + * @file attitude.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @brief Acquires sensor data and fuses it into attitude estimate for CC + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef ATTITUDE_H +#define ATTITUDE_H + +#include "openpilot.h" + +int32_t AttitudeInitialize(void); + +#endif // ATTITUDE_H diff --git a/shared/uavobjectdefinition/flightstatus.xml b/shared/uavobjectdefinition/flightstatus.xml index 22c4f9360..ba24d9bff 100644 --- a/shared/uavobjectdefinition/flightstatus.xml +++ b/shared/uavobjectdefinition/flightstatus.xml @@ -4,7 +4,7 @@ - + diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index 8a52b3b23..b9babcc4d 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -24,7 +24,7 @@ - + From 48362f56f6fb7b7d7816d16d303a0cdc9f1dbb35 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 31 Jul 2012 02:35:33 -0500 Subject: [PATCH 153/543] Enable autotune as an optional CC module --- flight/CopterControl/Makefile | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index 7c5498806..721ec1896 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -68,6 +68,7 @@ USE_GPS ?= YES USE_TXPID ?= YES USE_I2C ?= NO USE_ALTITUDE ?= NO +USE_AUTOTUNE ?= NO TEST_FAULTS ?= NO # List of optional modules to include @@ -94,6 +95,9 @@ endif ifeq ($(TEST_FAULTS), YES) OPTMODULES += Fault endif +ifeq ($(USE_AUTOTUNE), YES) +OPTMODULES += Autotune +endif # List of mandatory modules to include MODULES = Attitude Stabilization Actuator ManualControl FirmwareIAP @@ -204,6 +208,8 @@ SRC += $(OPUAVSYNTHDIR)/gpssettings.c SRC += $(OPUAVSYNTHDIR)/hwsettings.c SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c SRC += $(OPUAVSYNTHDIR)/receiveractivity.c +SRC += $(OPUAVSYNTHDIR)/relaytuningsettings.c +SRC += $(OPUAVSYNTHDIR)/relaytuning.c SRC += $(OPUAVSYNTHDIR)/taskinfo.c SRC += $(OPUAVSYNTHDIR)/mixerstatus.c SRC += $(OPUAVSYNTHDIR)/ratedesired.c From 17878b32f30ebe6dce7db72bae3a4ca6df111be1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 31 Jul 2012 09:49:17 -0500 Subject: [PATCH 154/543] Make autotune run within an attitude loop instead of direct rate mode. Easier for beginners. --- flight/Modules/Autotune/autotune.c | 19 ++++++++++++++----- flight/Modules/Stabilization/stabilization.c | 12 ++++++++++++ 2 files changed, 26 insertions(+), 5 deletions(-) diff --git a/flight/Modules/Autotune/autotune.c b/flight/Modules/Autotune/autotune.c index 3fc9246e4..754136b83 100644 --- a/flight/Modules/Autotune/autotune.c +++ b/flight/Modules/Autotune/autotune.c @@ -144,12 +144,21 @@ static void AutotuneTask(void *parameters) ManualControlCommandData manualControl; ManualControlCommandGet(&manualControl); - stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; - stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; - stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; + if (0) { // rate mode + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; - stabDesired.Roll = manualControl.Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL]; - stabDesired.Pitch = manualControl.Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH]; + stabDesired.Roll = manualControl.Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL]; + stabDesired.Pitch = manualControl.Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH]; + } else { + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + + stabDesired.Roll = manualControl.Roll * stabSettings.RollMax; + stabDesired.Pitch = manualControl.Pitch * stabSettings.PitchMax; + } + + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; stabDesired.Yaw = manualControl.Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW]; stabDesired.Throttle = manualControl.Throttle; diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index 87bee87cd..0b15b60cd 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -322,6 +322,18 @@ static void stabilizationTask(void* parameters) break; } + case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY: + case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE: + rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i], dT); + + if(rateDesiredAxis[i] > settings.MaximumRate[i]) + rateDesiredAxis[i] = settings.MaximumRate[i]; + else if(rateDesiredAxis[i] < -settings.MaximumRate[i]) + rateDesiredAxis[i] = -settings.MaximumRate[i]; + + + axis_lock_accum[i] = 0; + break; case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK: if (reinit) From c365a9c7ffb86613d2a3c886d0e9fbd9081f7f3d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 31 Jul 2012 17:38:21 -0500 Subject: [PATCH 155/543] Add stub for the autotune configuration widget --- .../src/plugins/config/autotune.ui | 940 ++++++++++++++++++ .../src/plugins/config/config.pro | 16 +- .../plugins/config/configautotunewidget.cpp | 31 + .../src/plugins/config/configautotunewidget.h | 55 + .../src/plugins/config/configgadgetwidget.cpp | 4 + .../src/plugins/config/configgadgetwidget.h | 2 +- 6 files changed, 1044 insertions(+), 4 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/config/autotune.ui create mode 100644 ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp create mode 100644 ground/openpilotgcs/src/plugins/config/configautotunewidget.h diff --git a/ground/openpilotgcs/src/plugins/config/autotune.ui b/ground/openpilotgcs/src/plugins/config/autotune.ui new file mode 100644 index 000000000..120caab94 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/autotune.ui @@ -0,0 +1,940 @@ + + + AutotuneWidget + + + + 0 + 0 + 443 + 505 + + + + Form + + + + + 20 + 10 + 401 + 121 + + + + Tuning Aggressiveness + + + + + + Rate Tuning: + + + + + + + Qt::Horizontal + + + + + + + Attitude Tuning: + + + + + + + Qt::Horizontal + + + + + + + + + 20 + 250 + 401 + 131 + + + + Computed Values + + + + + + RateKp + + + + + + + Roll + + + + + + + RateKi + + + + + + + AttitudeKp + + + + + + + AttitudeKi + + + + + + + Pitch + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + 20 + 140 + 401 + 101 + + + + Measured Values + + + + + + Roll: + + + + + + + 0 + + + + + + + 0 + + + + + + + Period + + + + + + + Amplitude + + + + + + + Pitch + + + + + + + 0 + + + + + + + 0 + + + + + + + + + 20 + 400 + 401 + 79 + + + + + 0 + 0 + + + + + 0 + 79 + + + + + 16777215 + 79 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + Qt::Horizontal + + + + 111 + 10 + + + + + + + + + 120 + 28 + + + + Reloads the saved settings into GCS. +Useful if you have accidentally changed some settings. + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Reload Board Data + + + + button:reload + buttongroup:10 + + + + + + + + + 60 + 28 + + + + Send settings to the board but do not save to the non-volatile memory + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Apply + + + + button:apply + + + + + + + + + 60 + 28 + + + + Send settings to the board and save to the non-volatile memory + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Save + + + + button:save + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/config.pro b/ground/openpilotgcs/src/plugins/config/config.pro index 8e49cb54d..1e0bdb3cb 100644 --- a/ground/openpilotgcs/src/plugins/config/config.pro +++ b/ground/openpilotgcs/src/plugins/config/config.pro @@ -36,7 +36,8 @@ HEADERS += configplugin.h \ cfg_vehicletypes/configfixedwingwidget.h \ cfg_vehicletypes/vehicleconfig.h \ configrevowidget.h \ - config_global.h + config_global.h \ + configautotunewidget.h SOURCES += configplugin.cpp \ configgadgetconfiguration.cpp \ configgadgetwidget.cpp \ @@ -67,7 +68,8 @@ SOURCES += configplugin.cpp \ cfg_vehicletypes/configfixedwingwidget.cpp \ cfg_vehicletypes/configccpmwidget.cpp \ outputchannelform.cpp \ - cfg_vehicletypes/vehicleconfig.cpp + cfg_vehicletypes/vehicleconfig.cpp \ + configautotunewidget.cpp FORMS += airframe.ui \ cc_hw_settings.ui \ pro_hw_settings.ui \ @@ -83,5 +85,13 @@ FORMS += airframe.ui \ outputchannelform.ui \ revosensors.ui \ txpid.ui \ - pipxtreme.ui + pipxtreme.ui \ + autotune.ui RESOURCES += configgadget.qrc + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp b/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp new file mode 100644 index 000000000..a64787580 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp @@ -0,0 +1,31 @@ + +#include "configautotunewidget.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +ConfigAutotuneWidget::ConfigAutotuneWidget(QWidget *parent) : + ConfigTaskWidget(parent) +{ + m_autotune = new Ui_AutotuneWidget(); + m_autotune->setupUi(this); + + autoLoadWidgets(); + + disableMouseWheelEvents(); +} + +ConfigAutotuneWidget::~ConfigAutotuneWidget() +{ + // Do nothing +} + + + diff --git a/ground/openpilotgcs/src/plugins/config/configautotunewidget.h b/ground/openpilotgcs/src/plugins/config/configautotunewidget.h new file mode 100644 index 000000000..bdaa615de --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/configautotunewidget.h @@ -0,0 +1,55 @@ +/** + ****************************************************************************** + * + * @file configautotunewidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief The Configuration Gadget used to adjust or recalculate autotuning + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef CONFIGAUTOTUNE_H +#define CONFIGAUTOTUNE_H + +#include "ui_autotune.h" +#include "../uavobjectwidgetutils/configtaskwidget.h" +#include "extensionsystem/pluginmanager.h" +#include "uavobjectmanager.h" +#include "uavobject.h" +#include "stabilizationsettings.h" +#include "relaytuningsettings.h" +#include "relaytuning.h" +#include +#include + +class ConfigAutotuneWidget : public ConfigTaskWidget +{ + Q_OBJECT +public: + explicit ConfigAutotuneWidget(QWidget *parent = 0); + +private: + Ui_AutotuneWidget *m_autotune; +signals: + +public slots: + +}; + +#endif // CONFIGAUTOTUNE_H diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index c12dbaee8..5c4a38117 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -32,6 +32,7 @@ #include "configinputwidget.h" #include "configoutputwidget.h" #include "configstabilizationwidget.h" +#include "configautotunewidget.h" #include "configcamerastabilizationwidget.h" #include "configtxpidwidget.h" #include "config_pro_hw_widget.h" @@ -84,6 +85,9 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) qwd = new ConfigStabilizationWidget(this); ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, QIcon(":/configgadget/images/gyroscope.png"), QString("Stabilization")); + qwd = new ConfigAutotuneWidget(this); + ftw->insertTab(ConfigGadgetWidget::autotune, qwd, QIcon(":/configgadget/images/gyroscope.png"), QString("Autotune")); + qwd = new ConfigCameraStabilizationWidget(this); ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, QIcon(":/configgadget/images/camera.png"), QString("Camera Stab")); diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h index 5e9dc6e67..0479f5928 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h @@ -50,7 +50,7 @@ class ConfigGadgetWidget: public QWidget public: ConfigGadgetWidget(QWidget *parent = 0); ~ConfigGadgetWidget(); - enum widgetTabs {hardware=0, aircraft, input, output, sensors, stabilization, camerastabilization, txpid, pipxtreme}; + enum widgetTabs {hardware=0, aircraft, input, output, sensors, stabilization, camerastabilization, txpid, pipxtreme, autotune}; public slots: void onAutopilotConnect(); From dfd1aceb06be44c3ae019664c89877ac932dcd58 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 31 Jul 2012 18:04:42 -0500 Subject: [PATCH 156/543] More work on autotune from GCS --- .../src/plugins/config/autotune.ui | 105 ++++++++++++++---- .../plugins/config/configautotunewidget.cpp | 6 - .../relaytuningsettings.xml | 2 + 3 files changed, 87 insertions(+), 26 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/autotune.ui b/ground/openpilotgcs/src/plugins/config/autotune.ui index 120caab94..55e4448a0 100644 --- a/ground/openpilotgcs/src/plugins/config/autotune.ui +++ b/ground/openpilotgcs/src/plugins/config/autotune.ui @@ -7,7 +7,7 @@ 0 0 443 - 505 + 560 @@ -19,39 +19,77 @@ 20 10 401 - 121 + 131 Tuning Aggressiveness - + Rate Tuning: - + Qt::Horizontal + + + obj1name:RelayTuningSettings + fieldname:RateGain + scale:0.01 + haslimits:yes + + - + Attitude Tuning: - + Qt::Horizontal + + + obj1name:RelayTuningSettings + fieldname:AttitudeGain + elemescale:0.01 + haslimits:yes + + + + + + + + StepSize + + + + + + + Qt::Horizontal + + + + obj1name:RelatyTuningSettings + fieldname:Amplitude + scale:0.01 + haslimits:yes + + @@ -62,7 +100,7 @@ 20 250 401 - 131 + 121 @@ -112,56 +150,56 @@ - + 0 - + 0 - + 0 - + 0 - + 0 - + 0 - + 0 - + 0 @@ -175,11 +213,11 @@ 20 140 401 - 101 + 111 - Measured Values + Measured Properties @@ -206,14 +244,14 @@ - Period + Period (ms) - Amplitude + Amplitude (deg/s) @@ -244,7 +282,7 @@ 20 - 400 + 480 401 79 @@ -934,6 +972,33 @@ border-radius: 4; + + + + 30 + 440 + 371 + 31 + + + + The buttons below change the autotuning settings which +will alter thingsfor the next autotuning flight + + + + + + 270 + 380 + 161 + 24 + + + + Use Computed Values + + diff --git a/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp b/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp index a64787580..4e61f473b 100644 --- a/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp @@ -22,10 +22,4 @@ ConfigAutotuneWidget::ConfigAutotuneWidget(QWidget *parent) : disableMouseWheelEvents(); } -ConfigAutotuneWidget::~ConfigAutotuneWidget() -{ - // Do nothing -} - - diff --git a/shared/uavobjectdefinition/relaytuningsettings.xml b/shared/uavobjectdefinition/relaytuningsettings.xml index 46a5bc124..c73f786e7 100644 --- a/shared/uavobjectdefinition/relaytuningsettings.xml +++ b/shared/uavobjectdefinition/relaytuningsettings.xml @@ -1,6 +1,8 @@ Setting to run a relay tuning algorithm + + From 52ffec0be4ec8beb208845984e9407e1b23996d1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 31 Jul 2012 21:39:26 -0500 Subject: [PATCH 157/543] Increase the initial tuning amplitude to 0.15 --- shared/uavobjectdefinition/relaytuningsettings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/relaytuningsettings.xml b/shared/uavobjectdefinition/relaytuningsettings.xml index c73f786e7..37b60f740 100644 --- a/shared/uavobjectdefinition/relaytuningsettings.xml +++ b/shared/uavobjectdefinition/relaytuningsettings.xml @@ -3,7 +3,7 @@ Setting to run a relay tuning algorithm - + From 5c00451c9ed2d0901f0af79aaaf4c24e31204a3e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 1 Aug 2012 01:13:05 -0500 Subject: [PATCH 158/543] Remove unused value field from the relaytuning object --- shared/uavobjectdefinition/relaytuning.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/shared/uavobjectdefinition/relaytuning.xml b/shared/uavobjectdefinition/relaytuning.xml index ef54f8b7f..297b44686 100644 --- a/shared/uavobjectdefinition/relaytuning.xml +++ b/shared/uavobjectdefinition/relaytuning.xml @@ -1,7 +1,6 @@ The input to the relay tuning. - From 7ea14ecc22fa0dac3155f9bbb06209d5ae255d04 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 1 Aug 2012 01:21:57 -0500 Subject: [PATCH 159/543] Track the output gain instead of amplitude so the measured values are consistent if the settings are changed afterwards. --- flight/Modules/Autotune/autotune.c | 5 +---- shared/uavobjectdefinition/relaytuning.xml | 2 +- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/flight/Modules/Autotune/autotune.c b/flight/Modules/Autotune/autotune.c index 754136b83..41e8a9542 100644 --- a/flight/Modules/Autotune/autotune.c +++ b/flight/Modules/Autotune/autotune.c @@ -254,16 +254,13 @@ static void update_stabilization_settings() const float gain_ratio_p = 1.0f / 5.0f; const float zero_ratio_p = 1.0f / 5.0f; - float input = relaySettings.Amplitude * 4.0f / M_PI; // amplitude of input (fundamental component of fourier series for the square wave) - // For now just run over roll and pitch for (uint i = 0; i < 2; i++) { - float output = relayTuning.Amplitude[i]; // amplitude of sinusoidal oscillation in output float wu = 1000.0f * 2 * M_PI / relayTuning.Period[i]; // ultimate freq = output osc freq (rad/s) float wc = wu * gain_ratio_r; // target openloop crossover frequency (rad/s) float zc = wc * zero_ratio_r; // controller zero location (rad/s) - float kpu = input / output; // ultimate gain, i.e. the proportional gain for instablity + float kpu = 4.0f / M_PI / relayTuning.Gain[i]; // ultimate gain, i.e. the proportional gain for instablity float kp = kpu * gain_ratio_r; // proportional gain float ki = zc * kp; // integral gain diff --git a/shared/uavobjectdefinition/relaytuning.xml b/shared/uavobjectdefinition/relaytuning.xml index 297b44686..d781e45ca 100644 --- a/shared/uavobjectdefinition/relaytuning.xml +++ b/shared/uavobjectdefinition/relaytuning.xml @@ -2,7 +2,7 @@ The input to the relay tuning. - + From 28539a80d19edc861cecd8b2ed0d25e32e4936ac Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 1 Aug 2012 01:38:40 -0500 Subject: [PATCH 160/543] Change default tuning settings --- shared/uavobjectdefinition/relaytuningsettings.xml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/shared/uavobjectdefinition/relaytuningsettings.xml b/shared/uavobjectdefinition/relaytuningsettings.xml index 37b60f740..abfa78a2a 100644 --- a/shared/uavobjectdefinition/relaytuningsettings.xml +++ b/shared/uavobjectdefinition/relaytuningsettings.xml @@ -1,9 +1,11 @@ Setting to run a relay tuning algorithm - - + + + + From 24d9e50c0808aaff47a23b36517958ba9b984f07 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 1 Aug 2012 02:09:10 -0500 Subject: [PATCH 161/543] Based on the selected behavior either apply or save the stabilization settings --- flight/Modules/Autotune/autotune.c | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/flight/Modules/Autotune/autotune.c b/flight/Modules/Autotune/autotune.c index 41e8a9542..1a26115ff 100644 --- a/flight/Modules/Autotune/autotune.c +++ b/flight/Modules/Autotune/autotune.c @@ -288,7 +288,19 @@ static void update_stabilization_settings() break; } } - StabilizationSettingsSet(&stabSettings); + switch(relaySettings.Behavior) { + case RELAYTUNINGSETTINGS_BEHAVIOR_MEASURE: + // Just measure, don't update the stab settings + break; + case RELAYTUNINGSETTINGS_BEHAVIOR_COMPUTE: + StabilizationSettingsSet(&stabSettings); + break; + case RELAYTUNINGSETTINGS_BEHAVIOR_SAVE: + StabilizationSettingsSet(&stabSettings); + UAVObjSave(StabilizationSettingsHandle(), 0); + break; + } + } /** From 2ccd6605a465d9183352ad997e62f676dc8ac05c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 1 Aug 2012 02:56:08 -0500 Subject: [PATCH 162/543] Now the stabilization refactor is in we can make swapping between tuning the system in rate or attitude mode software configurable. --- flight/Modules/Autotune/autotune.c | 13 ++++++++++--- flight/Modules/ManualControl/manualcontrol.c | 9 ++++++--- .../uavobjectdefinition/manualcontrolsettings.xml | 6 +++--- shared/uavobjectdefinition/stabilizationdesired.xml | 2 +- 4 files changed, 20 insertions(+), 10 deletions(-) diff --git a/flight/Modules/Autotune/autotune.c b/flight/Modules/Autotune/autotune.c index 1a26115ff..776e9b842 100644 --- a/flight/Modules/Autotune/autotune.c +++ b/flight/Modules/Autotune/autotune.c @@ -144,7 +144,12 @@ static void AutotuneTask(void *parameters) ManualControlCommandData manualControl; ManualControlCommandGet(&manualControl); - if (0) { // rate mode + RelayTuningSettingsData relaySettings; + RelayTuningSettingsGet(&relaySettings); + + bool rate = relaySettings.Mode == RELAYTUNINGSETTINGS_MODE_RATE; + + if (rate) { // rate mode stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; @@ -188,7 +193,8 @@ static void AutotuneTask(void *parameters) diffTime = xTaskGetTickCount() - lastUpdateTime; // Run relay mode on the roll axis for the measurement time - stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = rate ? STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE : + STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE; if (diffTime > MEAURE_TIME) { // Move on to next state state = AT_PITCH; lastUpdateTime = xTaskGetTickCount(); @@ -200,7 +206,8 @@ static void AutotuneTask(void *parameters) diffTime = xTaskGetTickCount() - lastUpdateTime; // Run relay mode on the pitch axis for the measurement time - stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = rate ? STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE : + STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE; if (diffTime > MEAURE_TIME) { // Move on to next state state = AT_FINISHED; lastUpdateTime = xTaskGetTickCount(); diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index 3dc4c53bc..22ced4c82 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -589,7 +589,8 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Roll * stabSettings.RollMax : (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Roll : - (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : + (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : + (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) ? cmd->Roll * stabSettings.RollMax : 0; // this is an invalid mode ; stabilization.Pitch = (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Pitch : @@ -598,7 +599,8 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Pitch * stabSettings.PitchMax : (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Pitch : - (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : + (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : + (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) ? cmd->Pitch * stabSettings.PitchMax : 0; // this is an invalid mode stabilization.Yaw = (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Yaw : @@ -607,7 +609,8 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Yaw * stabSettings.YawMax : (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Yaw : - (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : + (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : + (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE) ? cmd->Yaw * stabSettings.YawMax : 0; // this is an invalid mode stabilization.Throttle = (cmd->Throttle < 0) ? -1 : cmd->Throttle; diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index b9babcc4d..6a4dab0a9 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -18,9 +18,9 @@ - - - + + + diff --git a/shared/uavobjectdefinition/stabilizationdesired.xml b/shared/uavobjectdefinition/stabilizationdesired.xml index f24dd9eeb..8c400e68d 100644 --- a/shared/uavobjectdefinition/stabilizationdesired.xml +++ b/shared/uavobjectdefinition/stabilizationdesired.xml @@ -6,7 +6,7 @@ - + From c3df203d7ccc4b2a2650fed7686de00fc567c76a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 1 Aug 2012 02:56:54 -0500 Subject: [PATCH 163/543] Make the autotune UI allow recomputing the values based on the measured system properties. --- .../src/plugins/config/autotune.ui | 163 +++++++++++++----- .../plugins/config/configautotunewidget.cpp | 113 +++++++++++- .../src/plugins/config/configautotunewidget.h | 5 + 3 files changed, 238 insertions(+), 43 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/autotune.ui b/ground/openpilotgcs/src/plugins/config/autotune.ui index 55e4448a0..113144535 100644 --- a/ground/openpilotgcs/src/plugins/config/autotune.ui +++ b/ground/openpilotgcs/src/plugins/config/autotune.ui @@ -7,7 +7,7 @@ 0 0 443 - 560 + 575 @@ -26,68 +26,52 @@ Tuning Aggressiveness - + Rate Tuning: - - - - Qt::Horizontal - - - - obj1name:RelayTuningSettings - fieldname:RateGain - scale:0.01 - haslimits:yes - - - - - + Attitude Tuning: - - + + + + 100 + Qt::Horizontal - obj1name:RelayTuningSettings - fieldname:AttitudeGain - elemescale:0.01 - haslimits:yes + objname:RelayTuningSettings + fieldname:RateGain + scale:0.01 + haslimits:no - - - - StepSize + + + + 100 - - - - Qt::Horizontal - obj1name:RelatyTuningSettings - fieldname:Amplitude + objname:RelayTuningSettings + fieldname:AttitudeGain scale:0.01 - haslimits:yes + haslimits:no @@ -232,13 +216,33 @@ 0 + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + objname:RelayTuning + fieldname:Period + element:Roll + + - + 0 + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + objname:RelayTuning + fieldname:Gain + element:Roll + + @@ -251,7 +255,7 @@ - Amplitude (deg/s) + Gain (deg/s) / output @@ -267,13 +271,33 @@ 0 + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + objname:RelayTuning + fieldname:Period + element:Pitch + + - + 0 + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + objname:RelayTuning + fieldname:Gain + element:Pitch + + @@ -989,14 +1013,69 @@ will alter thingsfor the next autotuning flight - 270 + 250 380 - 161 - 24 + 171 + 31 + + + + QPushButton { +border: 1px outset #999; +border-radius: 5; +background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); +} + +QPushButton:pressed { + + border-style: inset; + background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); + +} + + +QPushButton:hover { + border: 1px outset #999; +border-color: rgb(83, 83, 83); +border-radius: 4; + } + + + Apply Computed Values + + + + + + 40 + 410 + 104 + 20 - Use Computed Values + Step Size + + + + + + 149 + 410 + 266 + 20 + + + + Qt::Horizontal + + + + objname:RelayTuningSettings + fieldname:Amplitude + scale:0.01 + haslimits:no + diff --git a/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp b/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp index 4e61f473b..6bef18130 100644 --- a/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp @@ -10,6 +10,9 @@ #include #include #include +#include "relaytuningsettings.h" +#include "relaytuning.h" +#include "stabilizationsettings.h" ConfigAutotuneWidget::ConfigAutotuneWidget(QWidget *parent) : ConfigTaskWidget(parent) @@ -17,9 +20,117 @@ ConfigAutotuneWidget::ConfigAutotuneWidget(QWidget *parent) : m_autotune = new Ui_AutotuneWidget(); m_autotune->setupUi(this); + // Connect automatic signals autoLoadWidgets(); - disableMouseWheelEvents(); + + // Whenever any value changes compute new potential stabilization settings + connect(m_autotune->rateTuning, SIGNAL(valueChanged(int)), this, SLOT(recomputeStabilization())); + connect(m_autotune->attitudeTuning, SIGNAL(valueChanged(int)), this, SLOT(recomputeStabilization())); + + RelayTuning *relayTuning = RelayTuning::GetInstance(getObjectManager()); + Q_ASSERT(relayTuning); + if(relayTuning) + connect(relayTuning, SIGNAL(updateRequested(UAVObject*)), this, SLOT(recomputeStabilization())); + + // Connect the apply button for the stabilization settings + connect(m_autotune->useComputedValues, SIGNAL(pressed()), this, SLOT(saveStabilization())); } +/** + * Apply the stabilization settings computed + */ +void ConfigAutotuneWidget::saveStabilization() +{ + StabilizationSettings *stabilizationSettings = StabilizationSettings::GetInstance(getObjectManager()); + Q_ASSERT(stabilizationSettings); + if(!stabilizationSettings) + return; + // Make sure to recompute in case the other stab settings changed since + // the last time + recomputeStabilization(); + + // Apply this data to the board + stabilizationSettings->setData(stabSettings); + stabilizationSettings->updated(); +} + +/** + * Called whenever the gain ratios or measured values + * are changed + */ +void ConfigAutotuneWidget::recomputeStabilization() +{ + RelayTuningSettings *relayTuningSettings = RelayTuningSettings::GetInstance(getObjectManager()); + Q_ASSERT(relayTuningSettings); + if (!relayTuningSettings) + return; + + RelayTuning *relayTuning = RelayTuning::GetInstance(getObjectManager()); + Q_ASSERT(relayTuning); + if(!relayTuning) + return; + + StabilizationSettings *stabilizationSettings = StabilizationSettings::GetInstance(getObjectManager()); + Q_ASSERT(stabilizationSettings); + if(!stabilizationSettings) + return; + + RelayTuning::DataFields relayTuningData = relayTuning->getData(); + RelayTuningSettings::DataFields tuningSettingsData = relayTuningSettings->getData(); + stabSettings = stabilizationSettings->getData(); + + // Need to divide these by 100 because that is what the .ui file does + // to get the UAVO + const double gain_ratio_r = m_autotune->rateTuning->value() / 100.0; + const double zero_ratio_r = m_autotune->rateTuning->value() / 100.0; + const double gain_ratio_p = m_autotune->attitudeTuning->value() / 100.0; + const double zero_ratio_p = m_autotune->attitudeTuning->value() / 100.0; + + // For now just run over roll and pitch + for (int i = 0; i < 2; i++) { + if (relayTuningData.Period[i] == 0 || relayTuningData.Gain[i] == 0) + continue; + + double wu = 1000.0 * 2 * M_PI / relayTuningData.Period[i]; // ultimate freq = output osc freq (rad/s) + + double wc = wu * gain_ratio_r; // target openloop crossover frequency (rad/s) + double zc = wc * zero_ratio_r; // controller zero location (rad/s) + double kpu = 4.0f / M_PI / relayTuningData.Gain[i]; // ultimate gain, i.e. the proportional gain for instablity + double kp = kpu * gain_ratio_r; // proportional gain + double ki = zc * kp; // integral gain + + // Now calculate gains for the next loop out knowing it is the integral of + // the inner loop -- the plant is position/velocity = scale*1/s + double wc2 = wc * gain_ratio_p; // crossover of the attitude loop + double kp2 = wc2; // kp of attitude + double ki2 = wc2 * zero_ratio_p * kp2; // ki of attitude + + switch(i) { + case 0: // Roll + + stabSettings.RollRatePID[StabilizationSettings::ROLLRATEPID_KP] = kp; + stabSettings.RollRatePID[StabilizationSettings::ROLLRATEPID_KI] = ki; + stabSettings.RollPI[StabilizationSettings::ROLLPI_KP] = kp2; + stabSettings.RollPI[StabilizationSettings::ROLLPI_KI] = ki2; + break; + case 1: // Pitch + stabSettings.PitchRatePID[StabilizationSettings::PITCHRATEPID_KP] = kp; + stabSettings.PitchRatePID[StabilizationSettings::PITCHRATEPID_KI] = ki; + stabSettings.PitchPI[StabilizationSettings::PITCHPI_KP] = kp2; + stabSettings.PitchPI[StabilizationSettings::PITCHPI_KI] = ki2; + break; + } + } + + // Display these computed settings + m_autotune->rollRateKp->setText(QString().number(stabSettings.RollRatePID[StabilizationSettings::ROLLRATEPID_KP])); + m_autotune->rollRateKi->setText(QString().number(stabSettings.RollRatePID[StabilizationSettings::ROLLRATEPID_KI])); + m_autotune->rollAttitudeKp->setText(QString().number(stabSettings.RollPI[StabilizationSettings::ROLLPI_KP])); + m_autotune->rollAttitudeKi->setText(QString().number(stabSettings.RollPI[StabilizationSettings::ROLLPI_KI])); + m_autotune->pitchRateKp->setText(QString().number(stabSettings.PitchRatePID[StabilizationSettings::PITCHRATEPID_KP])); + m_autotune->pitchRateKi->setText(QString().number(stabSettings.PitchRatePID[StabilizationSettings::PITCHRATEPID_KI])); + m_autotune->pitchAttitudeKp->setText(QString().number(stabSettings.PitchPI[StabilizationSettings::PITCHPI_KP])); + m_autotune->pitchAttitudeKi->setText(QString().number(stabSettings.PitchPI[StabilizationSettings::PITCHPI_KI])); +} diff --git a/ground/openpilotgcs/src/plugins/config/configautotunewidget.h b/ground/openpilotgcs/src/plugins/config/configautotunewidget.h index bdaa615de..7a89ed373 100644 --- a/ground/openpilotgcs/src/plugins/config/configautotunewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configautotunewidget.h @@ -46,10 +46,15 @@ public: private: Ui_AutotuneWidget *m_autotune; + StabilizationSettings::DataFields stabSettings; + signals: public slots: +private slots: + void recomputeStabilization(); + void saveStabilization(); }; #endif // CONFIGAUTOTUNE_H From d0ef95ff9a9269171c2589359b96ba5651834bc1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 1 Aug 2012 03:08:51 -0500 Subject: [PATCH 164/543] Fix idiotic bug in the stab_refactor --- flight/Modules/Stabilization/stabilization.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index 0b15b60cd..6f398ed3e 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -245,7 +245,7 @@ static void stabilizationTask(void* parameters) for(uint8_t i=0; i< MAX_AXES; i++) { // Check whether this axis mode needs to be reinitialized - bool reinit = (stabDesired.StabilizationMode[i] == previous_mode[i]); + bool reinit = (stabDesired.StabilizationMode[i] != previous_mode[i]); previous_mode[i] = stabDesired.StabilizationMode[i]; // Apply the selected control law From 652647fc87ab8f8138d29896bce17b8346fc9f0b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 1 Aug 2012 11:04:37 -0500 Subject: [PATCH 165/543] Make autotuning module optional --- flight/Modules/Autotune/autotune.c | 29 ++++++++++++++++++----- flight/PiOS/Boards/STM32103CB_CC_Rev1.h | 1 + shared/uavobjectdefinition/hwsettings.xml | 2 +- shared/uavobjectdefinition/taskinfo.xml | 6 ++--- 4 files changed, 28 insertions(+), 10 deletions(-) diff --git a/flight/Modules/Autotune/autotune.c b/flight/Modules/Autotune/autotune.c index 776e9b842..ec44a7b72 100644 --- a/flight/Modules/Autotune/autotune.c +++ b/flight/Modules/Autotune/autotune.c @@ -50,6 +50,7 @@ #include "pios.h" #include "flightstatus.h" +#include "hwsettings.h" #include "manualcontrolcommand.h" #include "manualcontrolsettings.h" #include "relaytuning.h" @@ -67,6 +68,7 @@ enum AUTOTUNE_STATE {AT_INIT, AT_START, AT_ROLL, AT_PITCH, AT_FINISHED, AT_SET}; // Private variables static xTaskHandle taskHandle; +static bool autotuneEnabled; // Private functions static void AutotuneTask(void *parameters); @@ -79,6 +81,19 @@ static void update_stabilization_settings(); int32_t AutotuneInitialize(void) { // Create a queue, connect to manual control command and flightstatus +#ifdef MODULE_AUTOTUNE_BUILTIN + autotuneEnabled = true; +#else + HwSettingsInitialize(); + uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; + + HwSettingsOptionalModulesGet(optionalModules); + + if (optionalModules[HWSETTINGS_OPTIONALMODULES_AUTOTUNE] == HWSETTINGS_OPTIONALMODULES_ENABLED) + autotuneEnabled = true; + else + autotuneEnabled = false; +#endif return 0; } @@ -89,13 +104,13 @@ int32_t AutotuneInitialize(void) */ int32_t AutotuneStart(void) { - - // Start main task - xTaskCreate(AutotuneTask, (signed char *)"Autotune", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); + // Start main task if it is enabled + if(autotuneEnabled) { + xTaskCreate(AutotuneTask, (signed char *)"Autotune", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); - //TaskMonitorAdd(TASKINFO_RUNNING_ATTITUDE, taskHandle); - //PIOS_WDG_RegisterFlag(PIOS_WDG_ATTITUDE); - + TaskMonitorAdd(TASKINFO_RUNNING_AUTOTUNE, taskHandle); + PIOS_WDG_RegisterFlag(PIOS_WDG_AUTOTUNE); + } return 0; } @@ -113,6 +128,8 @@ static void AutotuneTask(void *parameters) portTickType lastUpdateTime = xTaskGetTickCount(); while(1) { + + PIOS_WDG_UpdateFlag(PIOS_WDG_AUTOTUNE); // TODO: // 1. get from queue // 2. based on whether it is flightstatus or manualcontrol diff --git a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h index 10a7a41cd..85143fc17 100644 --- a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h @@ -74,6 +74,7 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1 #define PIOS_WDG_STABILIZATION 0x0002 #define PIOS_WDG_ATTITUDE 0x0004 #define PIOS_WDG_MANUAL 0x0008 +#define PIOS_WDG_AUTOTUNE 0x0010 //------------------------ // TELEMETRY diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 0cee2a6d9..0a09a7620 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -18,7 +18,7 @@ - + diff --git a/shared/uavobjectdefinition/taskinfo.xml b/shared/uavobjectdefinition/taskinfo.xml index 40f0d4bdf..97582f7e5 100644 --- a/shared/uavobjectdefinition/taskinfo.xml +++ b/shared/uavobjectdefinition/taskinfo.xml @@ -1,9 +1,9 @@ Task information - - - + + + From 561cf994b0cbba6c756fad3f653e6cf84d6bd7d0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 1 Aug 2012 12:07:52 -0500 Subject: [PATCH 166/543] Reduce the memory footprint of the sin lookup table by using sin(x+pi) = -sin(x). Still just needs to move into flash and have some options about precision when in its own library function. --- flight/Modules/Autotune/autotune.c | 2 +- flight/Modules/Stabilization/stabilization.c | 21 ++++++++++++++------ 2 files changed, 16 insertions(+), 7 deletions(-) diff --git a/flight/Modules/Autotune/autotune.c b/flight/Modules/Autotune/autotune.c index ec44a7b72..7073d6395 100644 --- a/flight/Modules/Autotune/autotune.c +++ b/flight/Modules/Autotune/autotune.c @@ -60,7 +60,7 @@ #include // Private constants -#define STACK_SIZE_BYTES 1024 +#define STACK_SIZE_BYTES 824 #define TASK_PRIORITY (tskIDLE_PRIORITY+2) // Private types diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index 6f398ed3e..a37b1aca5 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -92,7 +92,7 @@ int8_t vbar_gyros_suppress; bool vbar_piro_comp = false; // TODO: Move this to flash -static float sin_lookup[360]; +static float sin_lookup[180]; // Private functions static void stabilizationTask(void* parameters); @@ -101,6 +101,15 @@ static float bound(float val, float range); static void ZeroPids(void); static void SettingsUpdatedCb(UAVObjEvent * ev); +//! Uses the lookup table to calculate sine (angle is in degrees) +static float sin_l(int angle) { + angle = angle % 360; + if (angle > 180) + return - sin_lookup[angle-180]; + else + return sin_lookup[angle]; +} + /** * Module initialization */ @@ -110,7 +119,7 @@ int32_t StabilizationStart() // Create object queue queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); - for(uint32_t i = 0; i < 360; i++) + for(uint32_t i = 0; i < 180; i++) sin_lookup[i] = sinf((float)i * 2 * M_PI / 360.0f); // Listen for updates. @@ -409,8 +418,8 @@ static void stabilizationTask(void* parameters) uint32_t phase = 360 * dT / relay.Period[i]; if(phase >= 360) phase = 1; - accum_sin += sin_lookup[phase] * error; - accum_cos += sin_lookup[(phase + 90) % 360] * error; + accum_sin += sin_l(phase) * error; + accum_cos += sin_l(phase + 90) * error; accumulated ++; // Make susre we've had enough time since last transition then check for a change in the output @@ -491,8 +500,8 @@ static void stabilizationTask(void* parameters) uint32_t phase = 360 * dT / relay.Period[i]; if(phase >= 360) phase = 1; - accum_sin += sin_lookup[phase] * error; - accum_cos += sin_lookup[(phase + 90) % 360] * error; + accum_sin += sin_l(phase) * error; + accum_cos += sin_l(phase + 90) * error; accumulated ++; // Make susre we've had enough time since last transition then check for a change in the output From ee4bb84e362aa4032eaf6de08ed3a0ddfdef3f23 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 1 Aug 2012 12:20:36 -0500 Subject: [PATCH 167/543] Fix: Increase teh memory for autotune back to 1024 which leaves 100 free. --- flight/Modules/Autotune/autotune.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/Autotune/autotune.c b/flight/Modules/Autotune/autotune.c index 7073d6395..ec44a7b72 100644 --- a/flight/Modules/Autotune/autotune.c +++ b/flight/Modules/Autotune/autotune.c @@ -60,7 +60,7 @@ #include // Private constants -#define STACK_SIZE_BYTES 824 +#define STACK_SIZE_BYTES 1024 #define TASK_PRIORITY (tskIDLE_PRIORITY+2) // Private types From 8565dfbcc3c415b20775101d7a8452b2cc7991d7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 1 Aug 2012 17:52:53 -0500 Subject: [PATCH 168/543] Factor the relay tuning out of the main stabilization.c file into it's own tool. --- .../Modules/Stabilization/inc/relay_tuning.h | 40 ++++ flight/Modules/Stabilization/relay_tuning.c | 179 ++++++++++++++++ flight/Modules/Stabilization/stabilization.c | 192 ++---------------- 3 files changed, 239 insertions(+), 172 deletions(-) create mode 100644 flight/Modules/Stabilization/inc/relay_tuning.h create mode 100644 flight/Modules/Stabilization/relay_tuning.c diff --git a/flight/Modules/Stabilization/inc/relay_tuning.h b/flight/Modules/Stabilization/inc/relay_tuning.h new file mode 100644 index 000000000..d788ae62e --- /dev/null +++ b/flight/Modules/Stabilization/inc/relay_tuning.h @@ -0,0 +1,40 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup StabilizationModule Stabilization Module + * @brief Relay tuning controller + * @note This object updates the @ref ActuatorDesired "Actuator Desired" based on the + * PID loops on the @ref AttitudeDesired "Attitude Desired" and @ref AttitudeActual "Attitude Actual" + * @{ + * + * @file relay_tuning.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Attitude stabilization module. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef RELAY_TUNING_H +#define RELAY_TUNING_H + +int stabilization_relay_init(); +int stabilization_relay_rate(float err, float *output, int axis, bool reinit); + +#endif \ No newline at end of file diff --git a/flight/Modules/Stabilization/relay_tuning.c b/flight/Modules/Stabilization/relay_tuning.c new file mode 100644 index 000000000..ad4c7e064 --- /dev/null +++ b/flight/Modules/Stabilization/relay_tuning.c @@ -0,0 +1,179 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup StabilizationModule Stabilization Module + * @brief Relay tuning controller + * @note This object updates the @ref ActuatorDesired "Actuator Desired" based on the + * PID loops on the @ref AttitudeDesired "Attitude Desired" and @ref AttitudeActual "Attitude Actual" + * @{ + * + * @file stabilization.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Attitude stabilization module. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "stabilization.h" +#include "stabilizationsettings.h" +#include "actuatordesired.h" +#include "ratedesired.h" +#include "relaytuning.h" +#include "relaytuningsettings.h" +#include "stabilizationdesired.h" +#include "attitudeactual.h" +#include "gyros.h" +#include "flightstatus.h" +#include "manualcontrol.h" // Just to get a macro +#include "CoordinateConversions.h" + +//! Private variables +static float *sin_lookup; // TODO: Move this to flash +static const int SIN_RESOLUTION = 180; + +//! Private methods +static float sin_l(int angle); + +#define MAX_AXES 3 + +int stabilization_relay_init() +{ + sin_lookup = (float *) pvPortMalloc(sizeof(float) * SIN_RESOLUTION); + if (sin_lookup == NULL) + return -1; + + for(uint32_t i = 0; i < 180; i++) + sin_lookup[i] = sinf((float)i * 2 * M_PI / 360.0f); + + return 0; +} + +/** + * Apply a step function for the stabilization controller and monitor the + * result + * + * Used to Replace the rate PID with a relay to measure the critical properties of this axis + * i.e. period and gain + */ +int stabilization_relay_rate(float error, float *output, int axis, bool reinit) +{ + RelayTuningData relay; + RelayTuningGet(&relay); + + static bool high = false; + static portTickType lastHighTime; + static portTickType lastLowTime; + + static float accum_sin, accum_cos; + static uint32_t accumulated = 0; + + const uint16_t DEGLITCH_TIME = 20; // ms + const float AMPLITUDE_ALPHA = 0.95; + const float PERIOD_ALPHA = 0.95; + + portTickType thisTime = xTaskGetTickCount(); + + static bool rateRelayRunning[MAX_AXES]; + + // On first run initialize estimates to something reasonable + if(reinit) { + rateRelayRunning[axis] = false; + relay.Period[axis] = 200; + relay.Gain[axis] = 0; + + accum_sin = 0; + accum_cos = 0; + accumulated = 0; + + // These should get reinitialized anyway + high = true; + lastHighTime = thisTime; + lastLowTime = thisTime; + RelayTuningSet(&relay); + } + + + RelayTuningSettingsData relaySettings; + RelayTuningSettingsGet(&relaySettings); + + // Compute output, simple threshold on error + *output = error > 0 ? relaySettings.Amplitude : -relaySettings.Amplitude; + + /**** The code below here is to estimate the properties of the oscillation ****/ + + // Make sure the period can't go below limit + if (relay.Period[axis] < DEGLITCH_TIME) + relay.Period[axis] = DEGLITCH_TIME; + + // Project the error onto a sine and cosine of the same frequency + // to accumulate the average amplitude + int dT = thisTime - lastHighTime; + uint32_t phase = 360 * dT / relay.Period[axis]; + if(phase >= 360) + phase = 1; + accum_sin += sin_l(phase) * error; + accum_cos += sin_l(phase + 90) * error; + accumulated ++; + + // Make sure we've had enough time since last transition then check for a change in the output + bool hysteresis = (high ? (thisTime - lastHighTime) : (thisTime - lastLowTime)) > DEGLITCH_TIME; + if ( !high && hysteresis && error > 0 ){ /* RISE DETECTED */ + float this_amplitude = 2 * sqrtf(accum_sin*accum_sin + accum_cos*accum_cos) / accumulated; + float this_gain = this_amplitude / relaySettings.Amplitude; + + accumulated = 0; + accum_sin = 0; + accum_cos = 0; + + if(rateRelayRunning[axis] == false) { + rateRelayRunning[axis] = true; + relay.Period[axis] = 200; + relay.Gain[axis] = 0; + } else { + // Low pass filter each amplitude and period + relay.Gain[axis] = relay.Gain[axis] * AMPLITUDE_ALPHA + this_gain * (1 - AMPLITUDE_ALPHA); + relay.Period[axis] = relay.Period[axis] * PERIOD_ALPHA + dT * (1 - PERIOD_ALPHA); + } + lastHighTime = thisTime; + high = true; + RelayTuningSet(&relay); + } else if ( high && hysteresis && error < 0 ) { /* FALL DETECTED */ + lastLowTime = thisTime; + high = false; + } + + return 0; +} + + +/** + * Uses the lookup table to calculate sine (angle is in degrees) + * @param[in] angle in degrees + * @returns sin(angle) + */ +static float sin_l(int angle) { + angle = angle % 360; + if (angle > 180) + return - sin_lookup[angle-180]; + else + return sin_lookup[angle]; +} + diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index a37b1aca5..4ffe9b944 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -45,6 +45,9 @@ #include "manualcontrol.h" // Just to get a macro #include "CoordinateConversions.h" +// Includes for various stabilization algorithms +#include "relay_tuning.h" + // Private constants #define MAX_QUEUE_SIZE 1 @@ -91,9 +94,6 @@ pid_type pids[PID_MAX]; int8_t vbar_gyros_suppress; bool vbar_piro_comp = false; -// TODO: Move this to flash -static float sin_lookup[180]; - // Private functions static void stabilizationTask(void* parameters); static float ApplyPid(pid_type * pid, const float err, float dT); @@ -101,15 +101,6 @@ static float bound(float val, float range); static void ZeroPids(void); static void SettingsUpdatedCb(UAVObjEvent * ev); -//! Uses the lookup table to calculate sine (angle is in degrees) -static float sin_l(int angle) { - angle = angle % 360; - if (angle > 180) - return - sin_lookup[angle-180]; - else - return sin_lookup[angle]; -} - /** * Module initialization */ @@ -119,8 +110,8 @@ int32_t StabilizationStart() // Create object queue queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); - for(uint32_t i = 0; i < 180; i++) - sin_lookup[i] = sinf((float)i * 2 * M_PI / 360.0f); + // This prepares this optional algorithm + stabilization_relay_init(); // Listen for updates. // AttitudeActualConnectQueue(queue); @@ -366,171 +357,28 @@ static void stabilizationTask(void* parameters) break; + case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE: + // Store to rate desired variable for storing to UAVO + rateDesiredAxis[i] = bound(attitudeDesiredAxis[i], settings.ManualRate[i]); + + // Run the relay controller which also estimates the oscillation parameters + stabilization_relay_rate(rateDesiredAxis[i] - gyro_filtered[i], &actuatorDesiredAxis[i], i, reinit); + actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0); + + break; + case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE: - { - RelayTuningData relay; - RelayTuningGet(&relay); - - static bool rateRelayRunning[MAX_AXES]; - - // On first run initialize estimates to something reasonable - if(reinit) { + if(reinit) pids[PID_ROLL + i].iAccumulator = 0; - rateRelayRunning[i] = false; - relay.Period[i] = 200; - relay.Gain[i] = 0; - } - // Replace the rate PID with a relay to measure the critical properties of this axis - // i.e. period and gain - // Compute the outer loop + // Compute the outer loop like attitude mode rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i], dT); rateDesiredAxis[i] = bound(rateDesiredAxis[i], settings.MaximumRate[i]); - // Store to rate desired variable for storing to UAVO - rateDesiredAxis[i] = bound(attitudeDesiredAxis[i], settings.ManualRate[i]); + // Run the relay controller which also estimates the oscillation parameters + stabilization_relay_rate(rateDesiredAxis[i] - gyro_filtered[i], &actuatorDesiredAxis[i], i, reinit); + actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0); - RelayTuningSettingsData relaySettings; - RelayTuningSettingsGet(&relaySettings); - float error = rateDesiredAxis[i] - gyro_filtered[i]; - float command = error > 0 ? relaySettings.Amplitude : -relaySettings.Amplitude; - actuatorDesiredAxis[i] = bound(command,1.0f); - - static bool high = false; - static portTickType lastHighTime; - static portTickType lastLowTime; - portTickType thisTime = xTaskGetTickCount(); - - static float accum_sin, accum_cos; - static uint32_t accumulated = 0; - - const uint16_t DEGLITCH_TIME = 20; // ms - const float AMPLITUDE_ALPHA = 0.95; - const float PERIOD_ALPHA = 0.95; - - // Make sure the period can't go below limit - if (relay.Period[i] < DEGLITCH_TIME) - relay.Period[i] = DEGLITCH_TIME; - - // Project the error onto a sine and cosine of the same frequency - // to accumulate the average amplitude - float dT = thisTime - lastHighTime; - uint32_t phase = 360 * dT / relay.Period[i]; - if(phase >= 360) - phase = 1; - accum_sin += sin_l(phase) * error; - accum_cos += sin_l(phase + 90) * error; - accumulated ++; - - // Make susre we've had enough time since last transition then check for a change in the output - bool hysteresis = (high ? (thisTime - lastHighTime) : (thisTime - lastLowTime)) > DEGLITCH_TIME; - if ( !high && hysteresis && error > 0 ){ /* RISE DETECTED */ - float this_amplitude = 2 * sqrtf(accum_sin*accum_sin + accum_cos*accum_cos) / accumulated; - float this_gain = this_amplitude / relaySettings.Amplitude; - - accumulated = 0; - accum_sin = 0; - accum_cos = 0; - - if(rateRelayRunning[i] == false) { - rateRelayRunning[i] = true; - relay.Period[i] = 200; - relay.Gain[i] = 0; - } else { - // Low pass filter each amplitude and period - relay.Gain[i] = relay.Gain[i] * AMPLITUDE_ALPHA + this_gain * (1 - AMPLITUDE_ALPHA); - relay.Period[i] = relay.Period[i] * PERIOD_ALPHA + dT * (1 - PERIOD_ALPHA); - } - lastHighTime = thisTime; - high = true; - RelayTuningSet(&relay); - } else if ( high && hysteresis && error < 0 ) { /* FALL DETECTED */ - lastLowTime = thisTime; - high = false; - } - - break; - } - case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE: - { - RelayTuningData relay; - RelayTuningGet(&relay); - - static bool rateRelayRunning[MAX_AXES]; - - // On first run initialize estimates to something reasonable - if(reinit) { - pids[PID_ROLL + i].iAccumulator = 0; - rateRelayRunning[i] = false; - relay.Period[i] = 200; - relay.Gain[i] = 0; - } - - // Replace the rate PID with a relay to measure the critical properties of this axis - // i.e. period and gain - - // Store to rate desired variable for storing to UAVO - rateDesiredAxis[i] = bound(attitudeDesiredAxis[i], settings.ManualRate[i]); - - RelayTuningSettingsData relaySettings; - RelayTuningSettingsGet(&relaySettings); - float error = rateDesiredAxis[i] - gyro_filtered[i]; - float command = error > 0 ? relaySettings.Amplitude : -relaySettings.Amplitude; - actuatorDesiredAxis[i] = bound(command,1.0); - - static bool high = false; - static portTickType lastHighTime; - static portTickType lastLowTime; - portTickType thisTime = xTaskGetTickCount(); - - static float accum_sin, accum_cos; - static uint32_t accumulated = 0; - - const uint16_t DEGLITCH_TIME = 20; // ms - const float AMPLITUDE_ALPHA = 0.95; - const float PERIOD_ALPHA = 0.95; - - // Make sure the period can't go below limit - if (relay.Period[i] < DEGLITCH_TIME) - relay.Period[i] = DEGLITCH_TIME; - - // Project the error onto a sine and cosine of the same frequency - // to accumulate the average amplitude - float dT = thisTime - lastHighTime; - uint32_t phase = 360 * dT / relay.Period[i]; - if(phase >= 360) - phase = 1; - accum_sin += sin_l(phase) * error; - accum_cos += sin_l(phase + 90) * error; - accumulated ++; - - // Make susre we've had enough time since last transition then check for a change in the output - bool hysteresis = (high ? (thisTime - lastHighTime) : (thisTime - lastLowTime)) > DEGLITCH_TIME; - if ( !high && hysteresis && error > 0 ){ /* RISE DETECTED */ - float this_amplitude = 2 * sqrtf(accum_sin*accum_sin + accum_cos*accum_cos) / accumulated; - float this_gain = this_amplitude / relaySettings.Amplitude; - - accumulated = 0; - accum_sin = 0; - accum_cos = 0; - - if(rateRelayRunning[i] == false) { - rateRelayRunning[i] = true; - relay.Period[i] = 200; - relay.Gain[i] = 0; - } else { - // Low pass filter each amplitude and period - relay.Gain[i] = relay.Gain[i] * AMPLITUDE_ALPHA + this_gain * (1 - AMPLITUDE_ALPHA); - relay.Period[i] = relay.Period[i] * PERIOD_ALPHA + dT * (1 - PERIOD_ALPHA); - } - lastHighTime = thisTime; - high = true; - RelayTuningSet(&relay); - } else if ( high && hysteresis && error < 0 ) { /* FALL DETECTED */ - lastLowTime = thisTime; - high = false; - } - } break; case STABILIZATIONDESIRED_STABILIZATIONMODE_NONE: From 924c91ce1e7055fb3e2ff6fa186d3284113d16fd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 01:20:57 -0500 Subject: [PATCH 169/543] Fix mistake from previous merge with duplicate the STABILIZATIONOMDE_ATTITUDE case --- flight/Modules/Stabilization/stabilization.c | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index 4ffe9b944..bc6887081 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -322,19 +322,6 @@ static void stabilizationTask(void* parameters) break; } - case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAY: - case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE: - rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i], dT); - - if(rateDesiredAxis[i] > settings.MaximumRate[i]) - rateDesiredAxis[i] = settings.MaximumRate[i]; - else if(rateDesiredAxis[i] < -settings.MaximumRate[i]) - rateDesiredAxis[i] = -settings.MaximumRate[i]; - - - axis_lock_accum[i] = 0; - break; - case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK: if (reinit) pids[PID_RATE_ROLL + i].iAccumulator = 0; From aae0e562c67841f1be16e99b133758f658a3c313 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 01:53:55 -0500 Subject: [PATCH 170/543] Create a sine lookup table that is cached in flash and make relay tuning start ot use this. --- flight/CopterControl/Makefile | 2 + flight/Libraries/math/sin_lookup.c | 99 +++++++++++++++++++ flight/Libraries/math/sin_lookup.h | 39 ++++++++ .../Modules/Stabilization/inc/relay_tuning.h | 1 - flight/Modules/Stabilization/relay_tuning.c | 44 +-------- flight/Modules/Stabilization/stabilization.c | 3 - 6 files changed, 143 insertions(+), 45 deletions(-) create mode 100644 flight/Libraries/math/sin_lookup.c create mode 100644 flight/Libraries/math/sin_lookup.h diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index 721ec1896..957089c12 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -268,6 +268,7 @@ SRC += $(PIOSCOMMON)/printf-stdarg.c ## Libraries for flight calculations SRC += $(FLIGHTLIB)/fifo_buffer.c SRC += $(FLIGHTLIB)/CoordinateConversions.c +SRC += $(FLIGHTLIB)/math/sin_lookup.c SRC += $(FLIGHTLIB)/taskmonitor.c ## CMSIS for STM32 @@ -369,6 +370,7 @@ EXTRAINCDIRS += $(OPUAVSYNTHDIR) EXTRAINCDIRS += $(PIOS) EXTRAINCDIRS += $(PIOSINC) EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(FLIGHTLIB)/math EXTRAINCDIRS += $(PIOSSTM32F10X) EXTRAINCDIRS += $(PIOSCOMMON) EXTRAINCDIRS += $(PIOSBOARDS) diff --git a/flight/Libraries/math/sin_lookup.c b/flight/Libraries/math/sin_lookup.c new file mode 100644 index 000000000..575f171d3 --- /dev/null +++ b/flight/Libraries/math/sin_lookup.c @@ -0,0 +1,99 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilot Math Utilities + * @{ + * @addtogroup Sine and cosine methods that use a cached lookup table + * @{ + * + * @file sin_lookup.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Sine lookup table from flash with 1 degree resolution + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "math.h" +#include "stdint.h" + + // This is a precomputed sin lookup table over 90 degrees that + const float sin_table[] = { + 0.000000f,0.017452f,0.034899f,0.052336f,0.069756f,0.087156f,0.104528f,0.121869f,0.139173f,0.156434f, + 0.173648f,0.190809f,0.207912f,0.224951f,0.241922f,0.258819f,0.275637f,0.292372f,0.309017f,0.325568f, + 0.342020f,0.358368f,0.374607f,0.390731f,0.406737f,0.422618f,0.438371f,0.453990f,0.469472f,0.484810f, + 0.500000f,0.515038f,0.529919f,0.544639f,0.559193f,0.573576f,0.587785f,0.601815f,0.615661f,0.629320f, + 0.642788f,0.656059f,0.669131f,0.681998f,0.694658f,0.707107f,0.719340f,0.731354f,0.743145f,0.754710f, + 0.766044f,0.777146f,0.788011f,0.798636f,0.809017f,0.819152f,0.829038f,0.838671f,0.848048f,0.857167f, + 0.866025f,0.874620f,0.882948f,0.891007f,0.898794f,0.906308f,0.913545f,0.920505f,0.927184f,0.933580f, + 0.939693f,0.945519f,0.951057f,0.956305f,0.961262f,0.965926f,0.970296f,0.974370f,0.978148f,0.981627f, + 0.984808f,0.987688f,0.990268f,0.992546f,0.994522f,0.996195f,0.997564f,0.998630f,0.999391f,0.999848f + }; + +/** + * Use the lookup table to return sine(angle) where angle is in radians + * to save flash this cheats and uses trig functions to only save + * 90 values + * @param[in] angle Angle in degrees + * @returns sin(angle) +*/ +float sin_lookup_deg(float angle) +{ + int i_ang = ((int32_t) angle) % 360; + if(i_ang > 270) // for 270 to 360 deg + return -sin_table[360 - i_ang]; + else if (i_ang > 180) // for 180 to 270 deg + return -sin_table[i_ang - 180]; + else if (i_ang > 90) // for 90 to 170 deg + return sin_table[180 - i_ang]; + else // for 0 to 90 deg + return sin_table[i_ang]; + + return 0; +} + +/** + * Get cos(angle) using the sine lookup table + * @param[in] angle Angle in degrees + * @returns cos(angle) + */ +float cos_lookup_deg(float angle) +{ + return sin_lookup_deg(angle + 90); +} + +/** + * Use the lookup table to return sine(angle) where angle is in radians + * @param[in] angle Angle in radians + * @returns sin(angle) + */ +float sin_lookup_rad(float angle) +{ + int degrees = angle * 180.0f / M_PI; + return sin_lookup_deg(degrees); +} + +/** + * Use the lookup table to return sine(angle) where angle is in radians + * @param[in] angle Angle in radians + * @returns cos(angle) + */ +float cos_lookup_rad(float angle) +{ + int degrees = angle * 180.0f / M_PI; + return cos_lookup_deg(degrees); +} \ No newline at end of file diff --git a/flight/Libraries/math/sin_lookup.h b/flight/Libraries/math/sin_lookup.h new file mode 100644 index 000000000..0e0edb274 --- /dev/null +++ b/flight/Libraries/math/sin_lookup.h @@ -0,0 +1,39 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilot Math Utilities + * @{ + * @addtogroup Sine and cosine methods that use a cached lookup table + * @{ + * + * @file sin_lookup.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Sine lookup table from flash with 1 degree resolution + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef SIN_LOOKUP_H +#define SIN_LOOKUP_H + +float sin_lookup_deg(float angle); +float cos_lookup_deg(float angle); +float sin_lookup_rad(float angle); +float cos_lookup_rad(float angle); + +#endif \ No newline at end of file diff --git a/flight/Modules/Stabilization/inc/relay_tuning.h b/flight/Modules/Stabilization/inc/relay_tuning.h index d788ae62e..9044986c5 100644 --- a/flight/Modules/Stabilization/inc/relay_tuning.h +++ b/flight/Modules/Stabilization/inc/relay_tuning.h @@ -34,7 +34,6 @@ #ifndef RELAY_TUNING_H #define RELAY_TUNING_H -int stabilization_relay_init(); int stabilization_relay_rate(float err, float *output, int axis, bool reinit); #endif \ No newline at end of file diff --git a/flight/Modules/Stabilization/relay_tuning.c b/flight/Modules/Stabilization/relay_tuning.c index ad4c7e064..16b4351fd 100644 --- a/flight/Modules/Stabilization/relay_tuning.c +++ b/flight/Modules/Stabilization/relay_tuning.c @@ -32,40 +32,15 @@ */ #include "openpilot.h" -#include "stabilization.h" -#include "stabilizationsettings.h" -#include "actuatordesired.h" -#include "ratedesired.h" #include "relaytuning.h" #include "relaytuningsettings.h" -#include "stabilizationdesired.h" -#include "attitudeactual.h" -#include "gyros.h" -#include "flightstatus.h" -#include "manualcontrol.h" // Just to get a macro -#include "CoordinateConversions.h" +#include "sin_lookup.h" //! Private variables -static float *sin_lookup; // TODO: Move this to flash static const int SIN_RESOLUTION = 180; -//! Private methods -static float sin_l(int angle); - #define MAX_AXES 3 -int stabilization_relay_init() -{ - sin_lookup = (float *) pvPortMalloc(sizeof(float) * SIN_RESOLUTION); - if (sin_lookup == NULL) - return -1; - - for(uint32_t i = 0; i < 180; i++) - sin_lookup[i] = sinf((float)i * 2 * M_PI / 360.0f); - - return 0; -} - /** * Apply a step function for the stabilization controller and monitor the * result @@ -129,8 +104,8 @@ int stabilization_relay_rate(float error, float *output, int axis, bool reinit) uint32_t phase = 360 * dT / relay.Period[axis]; if(phase >= 360) phase = 1; - accum_sin += sin_l(phase) * error; - accum_cos += sin_l(phase + 90) * error; + accum_sin += sin_lookup_deg(phase) * error; + accum_cos += sin_lookup_deg(phase + 90) * error; accumulated ++; // Make sure we've had enough time since last transition then check for a change in the output @@ -164,16 +139,3 @@ int stabilization_relay_rate(float error, float *output, int axis, bool reinit) } -/** - * Uses the lookup table to calculate sine (angle is in degrees) - * @param[in] angle in degrees - * @returns sin(angle) - */ -static float sin_l(int angle) { - angle = angle % 360; - if (angle > 180) - return - sin_lookup[angle-180]; - else - return sin_lookup[angle]; -} - diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index bc6887081..c72348aa8 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -110,9 +110,6 @@ int32_t StabilizationStart() // Create object queue queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); - // This prepares this optional algorithm - stabilization_relay_init(); - // Listen for updates. // AttitudeActualConnectQueue(queue); GyrosConnectQueue(queue); From 2723ff4be3081c1488428da20aad169c8588c423 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 03:24:18 -0500 Subject: [PATCH 171/543] Factor the virtual flybar code out of the stabilization module --- .../Modules/Stabilization/inc/stabilization.h | 2 + .../Modules/Stabilization/inc/virtualflybar.h | 42 +++++++ flight/Modules/Stabilization/stabilization.c | 50 ++------ flight/Modules/Stabilization/virtualflybar.c | 119 ++++++++++++++++++ 4 files changed, 170 insertions(+), 43 deletions(-) create mode 100644 flight/Modules/Stabilization/inc/virtualflybar.h create mode 100644 flight/Modules/Stabilization/virtualflybar.c diff --git a/flight/Modules/Stabilization/inc/stabilization.h b/flight/Modules/Stabilization/inc/stabilization.h index 89a816c24..ec0ae4e9f 100644 --- a/flight/Modules/Stabilization/inc/stabilization.h +++ b/flight/Modules/Stabilization/inc/stabilization.h @@ -33,6 +33,8 @@ #ifndef STABILIZATION_H #define STABILIZATION_H +enum {ROLL,PITCH,YAW,MAX_AXES}; + int32_t StabilizationInitialize(); #endif // STABILIZATION_H diff --git a/flight/Modules/Stabilization/inc/virtualflybar.h b/flight/Modules/Stabilization/inc/virtualflybar.h new file mode 100644 index 000000000..8ef54ce52 --- /dev/null +++ b/flight/Modules/Stabilization/inc/virtualflybar.h @@ -0,0 +1,42 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup StabilizationModule Stabilization Module + * @brief Virtual flybar mode + * @note This file implements the logic for a virtual flybar + * @{ + * + * @file virtualflybar.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Attitude stabilization module. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + #ifndef VIRTUALFLYBAR_H + #define VIRTUALFLYBAR_H + +#include "openpilot.h" +#include "stabilizationsettings.h" + +int stabilization_virtual_flybar(float gyro, float command, float *output, float dT, bool reinit, uint32_t axis, StabilizationSettingsData *settings); +int stabilization_virtual_flybar_pirocomp(float z_gyro, float dT); + + #endif /* VIRTUALFLYBAR_H */ \ No newline at end of file diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index c72348aa8..d36505d1d 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -47,6 +47,7 @@ // Includes for various stabilization algorithms #include "relay_tuning.h" +#include "virtualflybar.h" // Private constants #define MAX_QUEUE_SIZE 1 @@ -62,9 +63,6 @@ enum {PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_VBAR_ROLL, PID_VBAR_PITCH, PID_VBAR_YAW, PID_MAX}; -enum {ROLL,PITCH,YAW,MAX_AXES}; - - // Private types typedef struct { float p; @@ -80,7 +78,6 @@ static xTaskHandle taskHandle; static StabilizationSettingsData settings; static xQueueHandle queue; float gyro_alpha = 0; -float gyro_filtered[3] = {0,0,0}; float axis_lock_accum[3] = {0,0,0}; float vbar_sensitivity[3] = {1, 1, 1}; uint8_t max_axis_lock = 0; @@ -88,11 +85,8 @@ uint8_t max_axislock_rate = 0; float weak_leveling_kp = 0; uint8_t weak_leveling_max = 0; bool lowThrottleZeroIntegral; -float vbar_integral[3] = {0, 0, 0}; float vbar_decay = 0.991f; pid_type pids[PID_MAX]; -int8_t vbar_gyros_suppress; -bool vbar_piro_comp = false; // Private functions static void stabilizationTask(void* parameters); @@ -224,6 +218,7 @@ static void stabilizationTask(void* parameters) local_error[2] = fmodf(local_error[2] + 180, 360) - 180; #endif + float gyro_filtered[3]; gyro_filtered[0] = gyro_filtered[0] * gyro_alpha + gyrosData.x * (1 - gyro_alpha); gyro_filtered[1] = gyro_filtered[1] * gyro_alpha + gyrosData.y * (1 - gyro_alpha); gyro_filtered[2] = gyro_filtered[2] * gyro_alpha + gyrosData.z * (1 - gyro_alpha); @@ -278,32 +273,14 @@ static void stabilizationTask(void* parameters) break; case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR: - { - if(reinit) - vbar_integral[i] = 0; + // Store for debugging output rateDesiredAxis[i] = attitudeDesiredAxis[i]; - // Track the angle of the virtual flybar which includes a slow decay - vbar_integral[i] = vbar_integral[i] * vbar_decay + gyro_filtered[i] * dT; - vbar_integral[i] = bound(vbar_integral[i], settings.VbarMaxAngle); - - // Command signal can indicate how much to disregard the gyro feedback (fast flips) - float gyro_gain = 1.0f; - if (vbar_gyros_suppress > 0) { - gyro_gain = (1.0f - fabs(rateDesiredAxis[i]) * vbar_gyros_suppress / 100.0f); - gyro_gain = (gyro_gain < 0) ? 0 : gyro_gain; - } - - // Command signal is composed of stick input added to the gyro and virtual flybar - actuatorDesiredAxis[i] = rateDesiredAxis[i] * vbar_sensitivity[i] - - gyro_gain * (vbar_integral[i] * pids[PID_VBAR_ROLL + i].i + - gyro_filtered[i] * pids[PID_VBAR_ROLL + i].p); - - actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0f); + // Run a virtual flybar stabilization algorithm on this axis + stabilization_virtual_flybar(gyro_filtered[i], rateDesiredAxis[i], &actuatorDesiredAxis[i], dT, reinit, i, &settings); break; - } case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING: { if (reinit) @@ -374,19 +351,8 @@ static void stabilizationTask(void* parameters) } } - // Piro compensation rotates the virtual flybar by yaw step to keep it - // rotated to external world - if (vbar_piro_comp) { - const float F_PI = 3.14159f; - float cy = cosf(gyro_filtered[2] / 180.0f * F_PI * dT); - float sy = sinf(gyro_filtered[2] / 180.0f * F_PI * dT); - - float vbar_pitch = cy * vbar_integral[1] - sy * vbar_integral[0]; - float vbar_roll = sy * vbar_integral[1] + cy * vbar_integral[0]; - - vbar_integral[1] = vbar_pitch; - vbar_integral[0] = vbar_roll; - } + if (settings.VbarPiroComp == STABILIZATIONSETTINGS_VBARPIROCOMP_TRUE) + stabilization_virtual_flybar_pirocomp(gyro_filtered[2], dT); #if defined(DIAGNOSTICS) RateDesiredSet(&rateDesired); @@ -544,8 +510,6 @@ static void SettingsUpdatedCb(UAVObjEvent * ev) // Compute time constant for vbar decay term based on a tau vbar_decay = expf(-fakeDt / settings.VbarTau); - vbar_gyros_suppress = settings.VbarGyroSuppress; - vbar_piro_comp = settings.VbarPiroComp == STABILIZATIONSETTINGS_VBARPIROCOMP_TRUE; } diff --git a/flight/Modules/Stabilization/virtualflybar.c b/flight/Modules/Stabilization/virtualflybar.c new file mode 100644 index 000000000..bbfe69eae --- /dev/null +++ b/flight/Modules/Stabilization/virtualflybar.c @@ -0,0 +1,119 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup StabilizationModule Stabilization Module + * @brief Virtual flybar mode + * @note This file implements the logic for a virtual flybar + * @{ + * + * @file virtualflybar.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Attitude stabilization module. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "stabilization.h" +#include "stabilizationsettings.h" + +//! Private variables +static float vbar_integral[MAX_AXES]; +static float vbar_decay = 0.991f; + +//! Private methods +static float bound(float val, float range); + +int stabilization_virtual_flybar(float gyro, float command, float *output, float dT, bool reinit, uint32_t axis, StabilizationSettingsData *settings) +{ + float gyro_gain = 1.0f; + float kp = 0, ki = 0; + + if(reinit) + vbar_integral[axis] = 0; + + // Track the angle of the virtual flybar which includes a slow decay + vbar_integral[axis] = vbar_integral[axis] * vbar_decay + gyro * dT; + vbar_integral[axis] = bound(vbar_integral[axis], settings->VbarMaxAngle); + + // Command signal can indicate how much to disregard the gyro feedback (fast flips) + if (settings->VbarGyroSuppress > 0) { + gyro_gain = (1.0f - fabs(command) * settings->VbarGyroSuppress / 100.0f); + gyro_gain = (gyro_gain < 0) ? 0 : gyro_gain; + } + + // Get the settings for the correct axis + switch(axis) + { + case ROLL: + kp = settings->VbarRollPI[STABILIZATIONSETTINGS_VBARROLLPI_KP]; + ki = settings->VbarRollPI[STABILIZATIONSETTINGS_VBARROLLPI_KI]; + break; + case PITCH: + kp = settings->VbarPitchPI[STABILIZATIONSETTINGS_VBARROLLPI_KP]; + ki = settings->VbarPitchPI[STABILIZATIONSETTINGS_VBARROLLPI_KI]; + break; + case YAW: + kp = settings->VbarYawPI[STABILIZATIONSETTINGS_VBARROLLPI_KP]; + ki = settings->VbarYawPI[STABILIZATIONSETTINGS_VBARROLLPI_KI]; + break; + default: + PIOS_DEBUG_Assert(0); + } + + // Command signal is composed of stick input added to the gyro and virtual flybar + *output = command * settings->VbarSensitivity[axis] - + gyro_gain * (vbar_integral[axis] * ki + gyro * kp); + + return 0; +} + +/** + * Want to keep the virtual flybar fixed in world coordinates as we pirouette + * @param[in] z_gyro The deg/s of rotation along the z axis + * @param[in] dT The time since last sample + */ +int stabilization_virtual_flybar_pirocomp(float z_gyro, float dT) +{ + const float F_PI = (float) M_PI; + float cy = cosf(z_gyro / 180.0f * F_PI * dT); + float sy = sinf(z_gyro / 180.0f * F_PI * dT); + + float vbar_pitch = cy * vbar_integral[1] - sy * vbar_integral[0]; + float vbar_roll = sy * vbar_integral[1] + cy * vbar_integral[0]; + + vbar_integral[1] = vbar_pitch; + vbar_integral[0] = vbar_roll; + + return 0; +} + +/** + * Bound input value between limits + */ +static float bound(float val, float range) +{ + if(val < -range) { + val = -range; + } else if(val > range) { + val = range; + } + return val; +} From 50c764116255f9a7b7e38d4d0122777685e710cf Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 04:12:12 -0500 Subject: [PATCH 172/543] Move the PID methods into a standalone library --- flight/CopterControl/Makefile | 7 +- flight/Libraries/math/pid.c | 91 +++++++++++++++ flight/Libraries/math/pid.h | 49 ++++++++ flight/Modules/Stabilization/stabilization.c | 116 ++++++------------- 4 files changed, 181 insertions(+), 82 deletions(-) create mode 100644 flight/Libraries/math/pid.c create mode 100644 flight/Libraries/math/pid.h diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index 957089c12..7a56df860 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -115,6 +115,8 @@ OPTESTS = ./Tests OPMODULEDIR = ../Modules FLIGHTLIB = ../Libraries FLIGHTLIBINC = $(FLIGHTLIB)/inc +MATHLIB = ../Libraries/math +MATHLIBINC = ../Libraries/math PIOS = ../PiOS PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x @@ -268,8 +270,9 @@ SRC += $(PIOSCOMMON)/printf-stdarg.c ## Libraries for flight calculations SRC += $(FLIGHTLIB)/fifo_buffer.c SRC += $(FLIGHTLIB)/CoordinateConversions.c -SRC += $(FLIGHTLIB)/math/sin_lookup.c SRC += $(FLIGHTLIB)/taskmonitor.c +SRC += $(MATHLIB)/sin_lookup.c +SRC += $(MATHLIB)/pid.c ## CMSIS for STM32 SRC += $(CMSISDIR)/core_cm3.c @@ -370,7 +373,7 @@ EXTRAINCDIRS += $(OPUAVSYNTHDIR) EXTRAINCDIRS += $(PIOS) EXTRAINCDIRS += $(PIOSINC) EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(FLIGHTLIB)/math +EXTRAINCDIRS += $(MATHLIBINC) EXTRAINCDIRS += $(PIOSSTM32F10X) EXTRAINCDIRS += $(PIOSCOMMON) EXTRAINCDIRS += $(PIOSBOARDS) diff --git a/flight/Libraries/math/pid.c b/flight/Libraries/math/pid.c new file mode 100644 index 000000000..58f15ad1f --- /dev/null +++ b/flight/Libraries/math/pid.c @@ -0,0 +1,91 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilot Math Utilities + * @{ + * @addtogroup Sine and cosine methods that use a cached lookup table + * @{ + * + * @file pid.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Methods to work with PID structure + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "pid.h" + +//! Private method +static float bound(float val, float range); + +float pid_apply(struct pid *pid, const float err, float dT) +{ + float diff = (err - pid->lastErr); + pid->lastErr = err; + + // Scale up accumulator by 1000 while computing to avoid losing precision + pid->iAccumulator += err * (pid->i * dT * 1000.0f); + pid->iAccumulator = bound(pid->iAccumulator, pid->iLim * 1000.0f); + return ((err * pid->p) + pid->iAccumulator / 1000.0f + (diff * pid->d / dT)); +} + +/** + * Reset a bit + * @param[in] pid The pid to reset + */ +void pid_zero(struct pid *pid) +{ + if (!pid) + return; + + pid->iAccumulator = 0; + pid->lastErr = 0; +} + +/** + * Configure the settings for a pid structure + * @param[out] pid The PID structure to configure + * @param[in] p The proportional term + * @param[in] i The integral term + * @param[in] d The derivative term + */ +void pid_configure(struct pid *pid, float p, float i, float d, float iLim) +{ + if (!pid) + return; + + pid->p = p; + pid->i = i; + pid->d = d; + pid->iLim = iLim; +} + +/** + * Bound input value between limits + */ +static float bound(float val, float range) +{ + if(val < -range) { + val = -range; + } else if(val > range) { + val = range; + } + return val; +} + diff --git a/flight/Libraries/math/pid.h b/flight/Libraries/math/pid.h new file mode 100644 index 000000000..71f9eb56e --- /dev/null +++ b/flight/Libraries/math/pid.h @@ -0,0 +1,49 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilot Math Utilities + * @{ + * @addtogroup Sine and cosine methods that use a cached lookup table + * @{ + * + * @file pid.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Methods to work with PID structure + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PID_H +#define PID_H + +//! +struct pid { + float p; + float i; + float d; + float iLim; + float iAccumulator; + float lastErr; +}; + +//! Methods to use the pid structures +float pid_apply(struct pid *pid, const float err, float dT); +void pid_zero(struct pid *pid); +void pid_configure(struct pid *pid, float p, float i, float d, float iLim); + +#endif /* PID_H */ \ No newline at end of file diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index d36505d1d..188f556c8 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -43,7 +43,10 @@ #include "gyros.h" #include "flightstatus.h" #include "manualcontrol.h" // Just to get a macro + +// Math libraries #include "CoordinateConversions.h" +#include "pid.h" // Includes for various stabilization algorithms #include "relay_tuning.h" @@ -61,17 +64,7 @@ #define TASK_PRIORITY (tskIDLE_PRIORITY+4) #define FAILSAFE_TIMEOUT_MS 30 -enum {PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_VBAR_ROLL, PID_VBAR_PITCH, PID_VBAR_YAW, PID_MAX}; - -// Private types -typedef struct { - float p; - float i; - float d; - float iLim; - float iAccumulator; - float lastErr; -} pid_type; +enum {PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_MAX}; // Private variables static xTaskHandle taskHandle; @@ -79,18 +72,16 @@ static StabilizationSettingsData settings; static xQueueHandle queue; float gyro_alpha = 0; float axis_lock_accum[3] = {0,0,0}; -float vbar_sensitivity[3] = {1, 1, 1}; uint8_t max_axis_lock = 0; uint8_t max_axislock_rate = 0; float weak_leveling_kp = 0; uint8_t weak_leveling_max = 0; bool lowThrottleZeroIntegral; float vbar_decay = 0.991f; -pid_type pids[PID_MAX]; +struct pid pids[PID_MAX]; // Private functions static void stabilizationTask(void* parameters); -static float ApplyPid(pid_type * pid, const float err, float dT); static float bound(float val, float range); static void ZeroPids(void); static void SettingsUpdatedCb(UAVObjEvent * ev); @@ -251,7 +242,7 @@ static void stabilizationTask(void* parameters) rateDesiredAxis[i] = bound(attitudeDesiredAxis[i], settings.ManualRate[i]); // Compute the inner loop - actuatorDesiredAxis[i] = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); + actuatorDesiredAxis[i] = pid_apply(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0f); break; @@ -263,11 +254,11 @@ static void stabilizationTask(void* parameters) } // Compute the outer loop - rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i], dT); + rateDesiredAxis[i] = pid_apply(&pids[PID_ROLL + i], local_error[i], dT); rateDesiredAxis[i] = bound(rateDesiredAxis[i], settings.MaximumRate[i]); // Compute the inner loop - actuatorDesiredAxis[i] = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); + actuatorDesiredAxis[i] = pid_apply(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0f); break; @@ -291,7 +282,7 @@ static void stabilizationTask(void* parameters) // Compute desired rate as input biased towards leveling rateDesiredAxis[i] = attitudeDesiredAxis[i] + weak_leveling; - actuatorDesiredAxis[i] = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); + actuatorDesiredAxis[i] = pid_apply(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0f); break; @@ -308,12 +299,12 @@ static void stabilizationTask(void* parameters) // For weaker commands or no command simply attitude lock (almost) on no gyro change axis_lock_accum[i] += (attitudeDesiredAxis[i] - gyro_filtered[i]) * dT; axis_lock_accum[i] = bound(axis_lock_accum[i], max_axis_lock); - rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], axis_lock_accum[i], dT); + rateDesiredAxis[i] = pid_apply(&pids[PID_ROLL + i], axis_lock_accum[i], dT); } rateDesiredAxis[i] = bound(rateDesiredAxis[i], settings.MaximumRate[i]); - actuatorDesiredAxis[i] = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); + actuatorDesiredAxis[i] = pid_apply(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT); actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0f); break; @@ -333,7 +324,7 @@ static void stabilizationTask(void* parameters) pids[PID_ROLL + i].iAccumulator = 0; // Compute the outer loop like attitude mode - rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i], dT); + rateDesiredAxis[i] = pid_apply(&pids[PID_ROLL + i], local_error[i], dT); rateDesiredAxis[i] = bound(rateDesiredAxis[i], settings.MaximumRate[i]); // Run the relay controller which also estimates the oscillation parameters @@ -387,33 +378,15 @@ static void stabilizationTask(void* parameters) } } -/** - * Update one of the PID structures with the input error and timestep - * @param pid Pointer to the PID structure - * @param[in] err The error on for this controller - * @param[in] dT The time step since the last update - */ -float ApplyPid(pid_type * pid, const float err, float dT) -{ - float diff = (err - pid->lastErr); - pid->lastErr = err; - - // Scale up accumulator by 1000 while computing to avoid losing precision - pid->iAccumulator += err * (pid->i * dT * 1000.0f); - pid->iAccumulator = bound(pid->iAccumulator, pid->iLim * 1000.0f); - return ((err * pid->p) + pid->iAccumulator / 1000.0f + (diff * pid->d / dT)); -} - /** * Clear the accumulators and derivatives for all the axes */ static void ZeroPids(void) { - for(int8_t ct = 0; ct < PID_MAX; ct++) { - pids[ct].iAccumulator = 0.0f; - pids[ct].lastErr = 0.0f; - } + for(uint32_t i = 0; i < PID_MAX; i++) + pid_zero(&pids[i]); + for(uint8_t i = 0; i < 3; i++) axis_lock_accum[i] = 0.0f; } @@ -437,54 +410,37 @@ static void SettingsUpdatedCb(UAVObjEvent * ev) StabilizationSettingsGet(&settings); // Set the roll rate PID constants - pids[PID_RATE_ROLL].p = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP]; - pids[PID_RATE_ROLL].i = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI]; - pids[PID_RATE_ROLL].d = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD]; - pids[PID_RATE_ROLL].iLim = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT]; + pid_configure(&pids[PID_RATE_ROLL], settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP], + settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI], + pids[PID_RATE_ROLL].d = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD], + pids[PID_RATE_ROLL].iLim = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT]); // Set the pitch rate PID constants - pids[PID_RATE_PITCH].p = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP]; - pids[PID_RATE_PITCH].i = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI]; - pids[PID_RATE_PITCH].d = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD]; - pids[PID_RATE_PITCH].iLim = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT]; + pid_configure(&pids[PID_RATE_PITCH], settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP], + pids[PID_RATE_PITCH].i = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI], + pids[PID_RATE_PITCH].d = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD], + pids[PID_RATE_PITCH].iLim = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT]); // Set the yaw rate PID constants - pids[PID_RATE_YAW].p = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP]; - pids[PID_RATE_YAW].i = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI]; - pids[PID_RATE_YAW].d = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD]; - pids[PID_RATE_YAW].iLim = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT]; + pid_configure(&pids[PID_RATE_YAW], settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP], + pids[PID_RATE_YAW].i = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI], + pids[PID_RATE_YAW].d = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD], + pids[PID_RATE_YAW].iLim = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT]); // Set the roll attitude PI constants - pids[PID_ROLL].p = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP]; - pids[PID_ROLL].i = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI]; - pids[PID_ROLL].iLim = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT]; + pid_configure(&pids[PID_ROLL], settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP], + settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI], 0, + pids[PID_ROLL].iLim = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT]); // Set the pitch attitude PI constants - pids[PID_PITCH].p = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP]; - pids[PID_PITCH].i = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI]; - pids[PID_PITCH].iLim = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT]; + pid_configure(&pids[PID_PITCH], settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP], + pids[PID_PITCH].i = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI], 0, + settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT]); // Set the yaw attitude PI constants - pids[PID_YAW].p = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KP]; - pids[PID_YAW].i = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KI]; - pids[PID_YAW].iLim = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT]; - - // Set the roll attitude PI constants - pids[PID_VBAR_ROLL].p = settings.VbarRollPI[STABILIZATIONSETTINGS_VBARROLLPI_KP]; - pids[PID_VBAR_ROLL].i = settings.VbarRollPI[STABILIZATIONSETTINGS_VBARROLLPI_KI]; - - // Set the pitch attitude PI constants - pids[PID_VBAR_PITCH].p = settings.VbarPitchPI[STABILIZATIONSETTINGS_VBARPITCHPI_KP]; - pids[PID_VBAR_PITCH].i = settings.VbarPitchPI[STABILIZATIONSETTINGS_VBARPITCHPI_KI]; - - // Set the yaw attitude PI constants - pids[PID_VBAR_YAW].p = settings.VbarYawPI[STABILIZATIONSETTINGS_VBARYAWPI_KP]; - pids[PID_VBAR_YAW].i = settings.VbarYawPI[STABILIZATIONSETTINGS_VBARYAWPI_KI]; - - // Need to store the vbar sensitivity - vbar_sensitivity[0] = settings.VbarSensitivity[0]; - vbar_sensitivity[1] = settings.VbarSensitivity[1]; - vbar_sensitivity[2] = settings.VbarSensitivity[2]; + pid_configure(&pids[PID_YAW], settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KP], + settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KI], 0, + settings.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT]); // Maximum deviation to accumulate for axis lock max_axis_lock = settings.MaxAxisLock; From fc2f8376bc1dbf56279e72296fb1bd6fd0240358 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 04:31:17 -0500 Subject: [PATCH 173/543] Prevent an alarm from ManualControlCommand when using autotuning mode. --- flight/Modules/ManualControl/inc/manualcontrol.h | 5 +++-- flight/Modules/ManualControl/manualcontrol.c | 4 ++++ 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/flight/Modules/ManualControl/inc/manualcontrol.h b/flight/Modules/ManualControl/inc/manualcontrol.h index f71cdebde..b67366f92 100644 --- a/flight/Modules/ManualControl/inc/manualcontrol.h +++ b/flight/Modules/ManualControl/inc/manualcontrol.h @@ -32,7 +32,7 @@ #include "manualcontrolcommand.h" -typedef enum {FLIGHTMODE_UNDEFINED = 0, FLIGHTMODE_MANUAL = 1, FLIGHTMODE_STABILIZED = 2, FLIGHTMODE_GUIDANCE = 3} flightmode_path; +typedef enum {FLIGHTMODE_UNDEFINED = 0, FLIGHTMODE_MANUAL = 1, FLIGHTMODE_STABILIZED = 2, FLIGHTMODE_GUIDANCE = 3, FLIGHTMODE_TUNING = 4} flightmode_path; #define PARSE_FLIGHT_MODE(x) ( \ (x == FLIGHTSTATUS_FLIGHTMODE_MANUAL) ? FLIGHTMODE_MANUAL : \ @@ -41,7 +41,8 @@ typedef enum {FLIGHTMODE_UNDEFINED = 0, FLIGHTMODE_MANUAL = 1, FLIGHTMODE_STABIL (x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED3) ? FLIGHTMODE_STABILIZED : \ (x == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) ? FLIGHTMODE_GUIDANCE : \ (x == FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) ? FLIGHTMODE_GUIDANCE : \ - (x == FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) ? FLIGHTMODE_GUIDANCE : FLIGHTMODE_UNDEFINED \ + (x == FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) ? FLIGHTMODE_GUIDANCE : \ + (x == FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE) ? FLIGHTMODE_TUNING : FLIGHTMODE_UNDEFINED \ ) int32_t ManualControlInitialize(); diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index 22ced4c82..02c54b4a3 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -388,6 +388,10 @@ static void manualControlTask(void *parameters) case FLIGHTMODE_STABILIZED: updateStabilizationDesired(&cmd, &settings); break; + case FLIGHTMODE_TUNING: + // Tuning takes settings directly from manualcontrolcommand. No need to + // call anything else. This just avoids errors. + break; case FLIGHTMODE_GUIDANCE: switch(flightStatus.FlightMode) { case FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD: From 3982ad0046fe1e59512e2cfb547a6a15cfd1aabb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 04:32:59 -0500 Subject: [PATCH 174/543] Enable AUTOTUNE by default for CC --- flight/CopterControl/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index 7a56df860..8b74935c4 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -68,7 +68,7 @@ USE_GPS ?= YES USE_TXPID ?= YES USE_I2C ?= NO USE_ALTITUDE ?= NO -USE_AUTOTUNE ?= NO +USE_AUTOTUNE ?= YES TEST_FAULTS ?= NO # List of optional modules to include From 83c920799d47b827c9a3420142d8be2a798e3ae4 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 3 Aug 2012 09:24:26 -0700 Subject: [PATCH 175/543] TelemetryWidget: rescaled .svg; transparent background; hide data rates when not connected. --- .../src/plugins/coreplugin/images/tx-rx.svg | 35 ++++++++++++------- .../coreplugin/telemetrymonitorwidget.cpp | 19 +++++----- 2 files changed, 33 insertions(+), 21 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/tx-rx.svg b/ground/openpilotgcs/src/plugins/coreplugin/images/tx-rx.svg index 42d0f6d30..e69e36e19 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/images/tx-rx.svg +++ b/ground/openpilotgcs/src/plugins/coreplugin/images/tx-rx.svg @@ -9,11 +9,11 @@ xmlns="http://www.w3.org/2000/svg" xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd" xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape" - width="990" - height="765" + width="620.10828" + height="82.577499" id="svg2" version="1.1" - inkscape:version="0.48.2 r9819" + inkscape:version="0.48.3.1 r9886" sodipodi:docname="tx-rx.svg"> @@ -25,25 +25,32 @@ inkscape:pageopacity="0.0" inkscape:pageshadow="2" inkscape:zoom="0.58" - inkscape:cx="243.88087" - inkscape:cy="482.05004" + inkscape:cx="89.172147" + inkscape:cy="14.870213" inkscape:document-units="px" inkscape:current-layer="txrxBackground" showgrid="false" showguides="false" inkscape:guide-bbox="true" - inkscape:window-width="1463" + inkscape:window-width="1440" inkscape:window-height="686" inkscape:window-x="200" inkscape:window-y="200" - inkscape:window-maximized="0"> + inkscape:window-maximized="0" + fit-margin-top="0" + fit-margin-left="0" + fit-margin-right="0" + fit-margin-bottom="0" + borderlayer="false" + inkscape:showpageshadow="false" + showborder="true"> @@ -213,7 +220,7 @@ sodipodi:role="line">Tx + style="display:inline" + transform="translate(-154.70873,-215.24268)"> + style="display:inline" + transform="translate(-154.70873,-215.24268)"> setBackgroundBrush(Qt::transparent); + QGraphicsScene *scene = new QGraphicsScene(0,0,180,100, this); QSvgRenderer *renderer = new QSvgRenderer(); if (renderer->load(QString(":/core/images/tx-rx.svg"))) { @@ -146,10 +147,12 @@ void TelemetryMonitorWidget::showTelemetry() QRectF rect = graph->boundingRect(); txSpeed->setPos(rect.right() - 110, rect.top()); - txSpeed->setPlainText(QString("%0").arg(connected ? txValue : 0.0)); + txSpeed->setPlainText(QString("%0").arg(txValue)); + txSpeed->setVisible(connected); rxSpeed->setPos(rect.right() - 110, rect.top() + (rect.height() / 2)); - rxSpeed->setPlainText(QString("%0").arg(connected ? rxValue : 0.0)); + rxSpeed->setPlainText(QString("%0").arg(rxValue)); + rxSpeed->setVisible(connected); update(); } @@ -165,7 +168,7 @@ void TelemetryMonitorWidget::resizeEvent(QResizeEvent* event) { Q_UNUSED(event); - graph->setPos(0,-100); + graph->setPos(0,-130); fitInView(graph, Qt::KeepAspectRatio); } From 490955dbeaaaf016bcad0814adffaad3f2b21851 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 3 Aug 2012 11:34:05 -0500 Subject: [PATCH 176/543] Use cos_lookup instead of sin_looup(x+90) --- flight/Modules/Stabilization/relay_tuning.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/flight/Modules/Stabilization/relay_tuning.c b/flight/Modules/Stabilization/relay_tuning.c index 16b4351fd..5dc538b4a 100644 --- a/flight/Modules/Stabilization/relay_tuning.c +++ b/flight/Modules/Stabilization/relay_tuning.c @@ -100,12 +100,12 @@ int stabilization_relay_rate(float error, float *output, int axis, bool reinit) // Project the error onto a sine and cosine of the same frequency // to accumulate the average amplitude - int dT = thisTime - lastHighTime; - uint32_t phase = 360 * dT / relay.Period[axis]; + int32_t dT = thisTime - lastHighTime; + int32_t phase = (360 * dT) / relay.Period[axis]; if(phase >= 360) - phase = 1; + phase = 0; accum_sin += sin_lookup_deg(phase) * error; - accum_cos += sin_lookup_deg(phase + 90) * error; + accum_cos += cos_lookup_deg(phase) * error; accumulated ++; // Make sure we've had enough time since last transition then check for a change in the output From 9f3c8dddd39b503a5e1b085e7a62397ddf07c68a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 3 Aug 2012 12:15:57 -0500 Subject: [PATCH 177/543] Add a version of the sin lookup table that is in ram instead of flash --- flight/Libraries/math/sin_lookup.c | 50 ++++++++++++++++++++ flight/Libraries/math/sin_lookup.h | 1 + flight/Modules/Stabilization/relay_tuning.c | 4 +- flight/Modules/Stabilization/stabilization.c | 10 ++-- 4 files changed, 60 insertions(+), 5 deletions(-) diff --git a/flight/Libraries/math/sin_lookup.c b/flight/Libraries/math/sin_lookup.c index 575f171d3..2a5508fce 100644 --- a/flight/Libraries/math/sin_lookup.c +++ b/flight/Libraries/math/sin_lookup.c @@ -28,9 +28,14 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include "openpilot.h" #include "math.h" +#include "stdbool.h" #include "stdint.h" +#ifdef FLASH_TABLE + /** Version of the code which precomputes the lookup table in flash **/ + // This is a precomputed sin lookup table over 90 degrees that const float sin_table[] = { 0.000000f,0.017452f,0.034899f,0.052336f,0.069756f,0.087156f,0.104528f,0.121869f,0.139173f,0.156434f, @@ -44,6 +49,11 @@ 0.984808f,0.987688f,0.990268f,0.992546f,0.994522f,0.996195f,0.997564f,0.998630f,0.999391f,0.999848f }; +int sin_lookup_initalize() +{ + return 0; +} + /** * Use the lookup table to return sine(angle) where angle is in radians * to save flash this cheats and uses trig functions to only save @@ -66,6 +76,46 @@ float sin_lookup_deg(float angle) return 0; } +#else +/** Version of the code which allocates the lookup table in heap **/ + +const int SIN_RESOLUTION = 180; + +static float *sin_table; +int sin_lookup_initalize() +{ + // Previously initialized + if (sin_table) + return 0; + + sin_table = (float *) pvPortMalloc(sizeof(float) * SIN_RESOLUTION); + if (sin_table == NULL) + return -1; + + for(uint32_t i = 0; i < 180; i++) + sin_table[i] = sinf((float)i * 2 * M_PI / 360.0f); + + return 0; +} + + + +/** + * Uses the lookup table to calculate sine (angle is in degrees) + * @param[in] angle in degrees + * @returns sin(angle) + */ +float sin_lookup_deg(float angle) { + int i_ang = ((int32_t)angle) % 360; + if (i_ang > 180) + return - sin_table[i_ang-180]; + else + return sin_table[i_ang]; +} + +#endif + + /** * Get cos(angle) using the sine lookup table * @param[in] angle Angle in degrees diff --git a/flight/Libraries/math/sin_lookup.h b/flight/Libraries/math/sin_lookup.h index 0e0edb274..adc29f66a 100644 --- a/flight/Libraries/math/sin_lookup.h +++ b/flight/Libraries/math/sin_lookup.h @@ -31,6 +31,7 @@ #ifndef SIN_LOOKUP_H #define SIN_LOOKUP_H +int sin_lookup_initalize(); float sin_lookup_deg(float angle); float cos_lookup_deg(float angle); float sin_lookup_rad(float angle); diff --git a/flight/Modules/Stabilization/relay_tuning.c b/flight/Modules/Stabilization/relay_tuning.c index 5dc538b4a..0f0bb9d55 100644 --- a/flight/Modules/Stabilization/relay_tuning.c +++ b/flight/Modules/Stabilization/relay_tuning.c @@ -101,11 +101,11 @@ int stabilization_relay_rate(float error, float *output, int axis, bool reinit) // Project the error onto a sine and cosine of the same frequency // to accumulate the average amplitude int32_t dT = thisTime - lastHighTime; - int32_t phase = (360 * dT) / relay.Period[axis]; + float phase = ((float)360 * (float)dT) / relay.Period[axis]; if(phase >= 360) phase = 0; accum_sin += sin_lookup_deg(phase) * error; - accum_cos += cos_lookup_deg(phase) * error; + accum_cos += sin_lookup_deg(phase + 90) * error; accumulated ++; // Make sure we've had enough time since last transition then check for a change in the output diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index 188f556c8..c4cc801e8 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -47,6 +47,7 @@ // Math libraries #include "CoordinateConversions.h" #include "pid.h" +#include "sin_lookup.h" // Includes for various stabilization algorithms #include "relay_tuning.h" @@ -117,12 +118,15 @@ int32_t StabilizationInitialize() // Initialize variables StabilizationSettingsInitialize(); ActuatorDesiredInitialize(); - RelayTuningSettingsInitialize(); - RelayTuningInitialize(); #if defined(DIAGNOSTICS) RateDesiredInitialize(); #endif - + + // Code required for relay tuning + sin_lookup_initalize(); + RelayTuningSettingsInitialize(); + RelayTuningInitialize(); + return 0; } From f3dc2dc2ad43ff4364e60f7803edb612dc99c758 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 3 Aug 2012 12:31:15 -0500 Subject: [PATCH 178/543] Store 180 deg in flash now and even make the flash and ram version share a lookup method. Still don't get the same results. --- flight/Libraries/math/sin_lookup.c | 66 +++++++++++++----------------- 1 file changed, 28 insertions(+), 38 deletions(-) diff --git a/flight/Libraries/math/sin_lookup.c b/flight/Libraries/math/sin_lookup.c index 2a5508fce..a536f3f34 100644 --- a/flight/Libraries/math/sin_lookup.c +++ b/flight/Libraries/math/sin_lookup.c @@ -33,6 +33,7 @@ #include "stdbool.h" #include "stdint.h" +//#define FLASH_TABLE #ifdef FLASH_TABLE /** Version of the code which precomputes the lookup table in flash **/ @@ -46,7 +47,16 @@ 0.766044f,0.777146f,0.788011f,0.798636f,0.809017f,0.819152f,0.829038f,0.838671f,0.848048f,0.857167f, 0.866025f,0.874620f,0.882948f,0.891007f,0.898794f,0.906308f,0.913545f,0.920505f,0.927184f,0.933580f, 0.939693f,0.945519f,0.951057f,0.956305f,0.961262f,0.965926f,0.970296f,0.974370f,0.978148f,0.981627f, - 0.984808f,0.987688f,0.990268f,0.992546f,0.994522f,0.996195f,0.997564f,0.998630f,0.999391f,0.999848f + 0.984808f,0.987688f,0.990268f,0.992546f,0.994522f,0.996195f,0.997564f,0.998630f,0.999391f,0.999848f, + 1.000000f,0.999848f,0.999391f,0.998630f,0.997564f,0.996195f,0.994522f,0.992546f,0.990268f,0.987688f, + 0.984808f,0.981627f,0.978148f,0.974370f,0.970296f,0.965926f,0.961262f,0.956305f,0.951057f,0.945519f, + 0.939693f,0.933580f,0.927184f,0.920505f,0.913545f,0.906308f,0.898794f,0.891007f,0.882948f,0.874620f, + 0.866025f,0.857167f,0.848048f,0.838671f,0.829038f,0.819152f,0.809017f,0.798636f,0.788011f,0.777146f, + 0.766044f,0.754710f,0.743145f,0.731354f,0.719340f,0.707107f,0.694658f,0.681998f,0.669131f,0.656059f, + 0.642788f,0.629320f,0.615661f,0.601815f,0.587785f,0.573576f,0.559193f,0.544639f,0.529919f,0.515038f, + 0.500000f,0.484810f,0.469472f,0.453990f,0.438371f,0.422618f,0.406737f,0.390731f,0.374607f,0.358368f, + 0.342020f,0.325568f,0.309017f,0.292372f,0.275637f,0.258819f,0.241922f,0.224951f,0.207912f,0.190809f, + 0.173648f,0.156434f,0.139173f,0.121869f,0.104528f,0.087156f,0.069756f,0.052336f,0.034899f,0.017452f }; int sin_lookup_initalize() @@ -54,28 +64,6 @@ int sin_lookup_initalize() return 0; } -/** - * Use the lookup table to return sine(angle) where angle is in radians - * to save flash this cheats and uses trig functions to only save - * 90 values - * @param[in] angle Angle in degrees - * @returns sin(angle) -*/ -float sin_lookup_deg(float angle) -{ - int i_ang = ((int32_t) angle) % 360; - if(i_ang > 270) // for 270 to 360 deg - return -sin_table[360 - i_ang]; - else if (i_ang > 180) // for 180 to 270 deg - return -sin_table[i_ang - 180]; - else if (i_ang > 90) // for 90 to 170 deg - return sin_table[180 - i_ang]; - else // for 0 to 90 deg - return sin_table[i_ang]; - - return 0; -} - #else /** Version of the code which allocates the lookup table in heap **/ @@ -98,23 +86,25 @@ int sin_lookup_initalize() return 0; } - - -/** - * Uses the lookup table to calculate sine (angle is in degrees) - * @param[in] angle in degrees - * @returns sin(angle) - */ -float sin_lookup_deg(float angle) { - int i_ang = ((int32_t)angle) % 360; - if (i_ang > 180) - return - sin_table[i_ang-180]; - else - return sin_table[i_ang]; -} - #endif +/** + * Use the lookup table to return sine(angle) where angle is in radians + * to save flash this cheats and uses trig functions to only save + * 90 values + * @param[in] angle Angle in degrees + * @returns sin(angle) +*/ +float sin_lookup_deg(float angle) +{ + int i_ang = ((int32_t) angle) % 360; + if (i_ang > 180) // for 180 to 270 deg + return -sin_table[i_ang - 180]; + else // for 0 to 90 deg + return sin_table[i_ang]; + + return 0; +} /** * Get cos(angle) using the sine lookup table From ccbbda1b519e88fce3b796476d5bfde928d86826 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 3 Aug 2012 12:41:00 -0500 Subject: [PATCH 179/543] Make default tuning mode Attitude to make it easier on people like me :) --- shared/uavobjectdefinition/relaytuningsettings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/relaytuningsettings.xml b/shared/uavobjectdefinition/relaytuningsettings.xml index abfa78a2a..4ee3cb11b 100644 --- a/shared/uavobjectdefinition/relaytuningsettings.xml +++ b/shared/uavobjectdefinition/relaytuningsettings.xml @@ -4,7 +4,7 @@ - + From 8eac518a9c5bb5445f02b58708018ce4bf14265e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 3 Aug 2012 12:43:50 -0500 Subject: [PATCH 180/543] If the sin table is empty don't attempt to use it and return 0. --- flight/Libraries/math/sin_lookup.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/flight/Libraries/math/sin_lookup.c b/flight/Libraries/math/sin_lookup.c index a536f3f34..79798b3d4 100644 --- a/flight/Libraries/math/sin_lookup.c +++ b/flight/Libraries/math/sin_lookup.c @@ -97,6 +97,9 @@ int sin_lookup_initalize() */ float sin_lookup_deg(float angle) { + if (sin_table == NULL) + return 0; + int i_ang = ((int32_t) angle) % 360; if (i_ang > 180) // for 180 to 270 deg return -sin_table[i_ang - 180]; From 38e521fc1a2e38ffe4d6b8fdbe9dffc40c04eed4 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 3 Aug 2012 13:52:35 -0700 Subject: [PATCH 181/543] TelemetryWidget: set AlignCenter, chasing osx render correctness. --- .../src/plugins/coreplugin/telemetrymonitorwidget.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp index 5aff56e0a..d7f6b052c 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/telemetrymonitorwidget.cpp @@ -12,6 +12,7 @@ TelemetryMonitorWidget::TelemetryMonitorWidget(QWidget *parent) : QGraphicsView( setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + setAlignment(Qt::AlignCenter); setFrameStyle(QFrame::NoFrame); setStyleSheet("background:transparent;"); setAttribute(Qt::WA_TranslucentBackground); From b621b057b60e426ff191f1a983406b9134b514a8 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Fri, 3 Aug 2012 14:31:54 -0700 Subject: [PATCH 182/543] remove overo? --- overo | 1 - 1 file changed, 1 deletion(-) delete mode 160000 overo diff --git a/overo b/overo deleted file mode 160000 index 335a3486d..000000000 --- a/overo +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 335a3486dd41e48345209d0a65d49a8cc8b442a1 From 0d2e3078852a54caad993a9261eacbfdaaf24680 Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Fri, 3 Aug 2012 22:01:54 -0700 Subject: [PATCH 183/543] resized the save area on stabi page, added axislock and weakleveling to advanced menu --- .../src/plugins/config/stabilization.ui | 18439 ++++++++-------- 1 file changed, 9675 insertions(+), 8764 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index f00d8cdbf..84a668f09 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,8 +6,8 @@ 0 0 - 992 - 885 + 677 + 862 @@ -594,8 +594,8 @@ 0 0 - 962 - 754 + 647 + 761 @@ -6934,15 +6934,6739 @@ border-radius: 5; 0 0 - 962 - 754 + 632 + 823 true - - + + + + + + 0 + 0 + + + + + 0 + 230 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + Rate Stabization Coefficients (Inner Loop) + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + + + 4 + + + + + + + + Link Roll and Pitch + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:4 + + + + + + + + + + + 0 + 0 + + + + + 0 + 151 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + 2 + + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same +value as the Kp. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same +value as the Kp. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. +Then lower the value by 20% or so. + +You can usually go for higher values for Yaw factors. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. +Then lower the value by 20% or so. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. +Then lower the value by 20% or so. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same +value as the Kp. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 58 + 0 + + + + + 16777215 + 16777215 + + + + + + + Derivative + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 60 + 13 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 50 + 0 + + + + + 16777215 + 16777215 + + + + + + + ILimit + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + + + + + + + 0 + 0 + + + + + 0 + 210 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + Attitude Stabization Coefficients (Outer Loop) + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + + + 6 + + + + + + + + Link Roll and Pitch + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:5 + + + + + + + + + + + 0 + 0 + + + + + 0 + 131 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Ki + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Ki + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:ILimit + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 50 + 0 + + + + + 16777215 + 16777215 + + + + + + + ILimit + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 60 + 13 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Ki + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:ILimit + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:YawPI + element:ILimit + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + + + @@ -10228,8605 +16952,6 @@ border-radius: 5; - - - - - 0 - 0 - - - - - 0 - 230 - - - - - 16777215 - 16777215 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - Rate Stabization Coefficients (Inner Loop) - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - false - - - - - - 4 - - - - - - - - Link Roll and Pitch - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:4 - - - - - - - - - - - 0 - 0 - - - - - 0 - 151 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - 2 - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - -You can usually go for higher values for Yaw factors. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 58 - 0 - - - - - 16777215 - 16777215 - - - - - - - Derivative - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 60 - 13 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - - - - - - - 0 - 0 - - - - - 0 - 210 - - - - - 16777215 - 16777215 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - Attitude Stabization Coefficients (Outer Loop) - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - false - - - - - - 6 - - - - - - - - Link Roll and Pitch - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:5 - - - - - - - - - - - 0 - 0 - - - - - 0 - 131 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Preferred - - - - 60 - 13 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - Advanced - - - - 12 - - - 0 - - - - - - - - - - 255 - 255 - 255 - - - - - - - 240 - 240 - 240 - - - - - - - - - 255 - 255 - 255 - - - - - - - 240 - 240 - 240 - - - - - - - - - 240 - 240 - 240 - - - - - - - 240 - 240 - 240 - - - - - - - - QFrame::NoFrame - - - QFrame::Plain - - - true - - - - - 0 - 0 - 962 - 754 - - - - - - - - 0 - 100 - - - - Axis Lock - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Weak Leveling Kp (deg/s)/deg - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Weak Leveling Rate deg/s - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - - - - 0 - 100 - - - - Weak Leveling - - groupBox_2 - - - - - - - 0 - 150 - - - - ILimits - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 50 - 0 - - - - - 16777215 - 16777215 - - - - - - - ILimit Attitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:ILimit - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 110 - 13 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:ILimit - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:ILimit - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 50 - 0 - - - - - 16777215 - 16777215 - - - - - - - ILimit Rate Mode - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - @@ -21683,6 +19808,2778 @@ border-radius: 5; + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + Advanced + + + + 12 + + + 0 + + + + + + + + + + 255 + 255 + 255 + + + + + + + 240 + 240 + 240 + + + + + + + + + 255 + 255 + 255 + + + + + + + 240 + 240 + 240 + + + + + + + + + 240 + 240 + 240 + + + + + + + 240 + 240 + 240 + + + + + + + + QFrame::NoFrame + + + QFrame::Plain + + + true + + + + + 0 + 0 + 647 + 761 + + + + + + + + 0 + 100 + + + + false + + + Weak Leveling + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:10 + + + + + + + + + + Qt::Horizontal + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1.000000000000000 + + + 360.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaxWeakLevelingRate + haslimits:no + scale:1 + buttongroup:10 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 2 + + + 0.010000000000000 + + + 360.000000000000000 + + + 0.010000000000000 + + + + objname:StabilizationSettings + fieldname:WeakLevelingKp + haslimits:no + scale:1 + buttongroup:10 + + + + + + + + + 0 + 0 + + + + + 220 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Weak Leveling Kp ((deg/s)/deg) + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 220 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Weak Leveling Rate (deg/s) + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + + 0 + 100 + + + + false + + + Axis Lock + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:11 + + + + + + + + + + Qt::Horizontal + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 220 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Max Axis Lock Rate (deg/s) + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 0.000000000000000 + + + 360.000000000000000 + + + 1.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaxAxisLock + haslimits:no + scale:1 + buttongroup:11 + + + + + + + + + 0 + 0 + + + + + 220 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Max Axis Lock (deg) + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1.000000000000000 + + + 360.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaxAxisLockRate + haslimits:no + scale:1 + buttongroup:11 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + @@ -21762,13 +22659,13 @@ automatically every 300ms, which will help for fast tuning. 0 - 75 + 25 16777215 - 75 + 45 @@ -22294,9 +23191,12 @@ automatically every 300ms, which will help for fast tuning. Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - 4 + + + 0 + + + 0 @@ -22305,166 +23205,177 @@ automatically every 300ms, which will help for fast tuning. - 40 + 269 20 - - - 4 + + + + 0 + 0 + - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 32 - 32 - - - - Takes you to the wiki page - - - - - - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 32 - 32 - - - - true - - - - button:help - url:http://wiki.openpilot.org/x/DAO9 - - - - - - - - - 0 - 0 - - - - - 140 - 25 - - - - - 16777215 - 16777215 - - - - Reloads the saved settings into GCS. + + + 0 + 0 + + + + + 32 + 32 + + + + Takes you to the wiki page + + + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 25 + 25 + + + + true + + + + button:help + url:http://wiki.openpilot.org/x/DAO9 + + + + + + + + + 0 + 0 + + + + + 140 + 16 + + + + + 16777215 + 16777215 + + + + Reloads the saved settings into GCS. Useful if you have accidentally changed some settings. - - - - - - Reload Board Data - - - - button:reload - buttongroup:10 - - - - - - - - - 60 - 25 - - - - - 16777215 - 16777215 - - - - Send settings to the board but do not save to the non-volatile memory - - - - - - Apply - - - - button:apply - - - - - - - - - 60 - 25 - - - - - 16777215 - 16777215 - - - - Send settings to the board and save to the non-volatile memory - - - - - - Save - - - - button:save - - - - - + + + + + + Reload Board Data + + + + 16 + 16 + + + + + button:reload + buttongroup:10 + + + + + + + + + 0 + 0 + + + + + 60 + 16 + + + + + 16777215 + 16777215 + + + + Send settings to the board but do not save to the non-volatile memory + + + + + + Apply + + + + button:apply + + + + + + + + + 0 + 0 + + + + + 60 + 16 + + + + + 16777215 + 16777215 + + + + Send settings to the board and save to the non-volatile memory + + + + + + Save + + + + button:save + + + From d6c485459ff570e71d3ca9a2195f7da825fd89ff Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 00:31:45 -0500 Subject: [PATCH 184/543] Fix error Stac caught in sin_lookup --- flight/Libraries/math/sin_lookup.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Libraries/math/sin_lookup.c b/flight/Libraries/math/sin_lookup.c index 79798b3d4..4444d10d2 100644 --- a/flight/Libraries/math/sin_lookup.c +++ b/flight/Libraries/math/sin_lookup.c @@ -101,9 +101,9 @@ float sin_lookup_deg(float angle) return 0; int i_ang = ((int32_t) angle) % 360; - if (i_ang > 180) // for 180 to 270 deg + if (i_ang >= 180) // for 180 to 360 deg return -sin_table[i_ang - 180]; - else // for 0 to 90 deg + else // for 0 to 179 deg return sin_table[i_ang]; return 0; From 096f940fee2ea037d3ec701fe5ed48630f01d7db Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 12:03:41 -0500 Subject: [PATCH 185/543] Reenable the flash version now Stac's fix is tested. --- flight/Libraries/math/sin_lookup.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Libraries/math/sin_lookup.c b/flight/Libraries/math/sin_lookup.c index 4444d10d2..1e703b87f 100644 --- a/flight/Libraries/math/sin_lookup.c +++ b/flight/Libraries/math/sin_lookup.c @@ -33,7 +33,7 @@ #include "stdbool.h" #include "stdint.h" -//#define FLASH_TABLE +#define FLASH_TABLE #ifdef FLASH_TABLE /** Version of the code which precomputes the lookup table in flash **/ From d201cad7689d16b845ca5b5a1e983f483e50247f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 12:03:53 -0500 Subject: [PATCH 186/543] Connect correct signal to relay tuning so the UI populates the calculated stabilization settings. --- ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp b/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp index 6bef18130..33106be4c 100644 --- a/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp @@ -31,7 +31,7 @@ ConfigAutotuneWidget::ConfigAutotuneWidget(QWidget *parent) : RelayTuning *relayTuning = RelayTuning::GetInstance(getObjectManager()); Q_ASSERT(relayTuning); if(relayTuning) - connect(relayTuning, SIGNAL(updateRequested(UAVObject*)), this, SLOT(recomputeStabilization())); + connect(relayTuning, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(recomputeStabilization())); // Connect the apply button for the stabilization settings connect(m_autotune->useComputedValues, SIGNAL(pressed()), this, SLOT(saveStabilization())); From 72749a1ce1e6940b50e2d7348ac9a9f0c3b88205 Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sat, 4 Aug 2012 23:03:00 -0700 Subject: [PATCH 187/543] resized the default buttons areas, moved the entire sensor tuning to expert, still WIP --- .../src/plugins/config/stabilization.ui | 11793 ++++++++++------ 1 file changed, 7176 insertions(+), 4617 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 84a668f09..e91732607 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,8 +6,8 @@ 0 0 - 677 - 862 + 792 + 828 @@ -483,7 +483,7 @@ QTabWidget::Rounded - 0 + 1 false @@ -594,11 +594,11 @@ 0 0 - 647 - 761 + 762 + 727 - + 12 @@ -628,90 +628,86 @@ Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - 4 + + + 4 + + + + + + 0 + 0 + - - - - - 0 - 0 - - - - Qt::StrongFocus - - - - - - Link Roll and Pitch - - - - - - - Qt::Horizontal - - - QSizePolicy::MinimumExpanding - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - false - - - - - - Default - - - - button:default - buttongroup:1 - - - - - + + Qt::StrongFocus + + + + + + Link Roll and Pitch + + - + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 497 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + false + + + + + + Default + + + + button:default + buttongroup:1 + + + + + @@ -3999,81 +3995,77 @@ value as the Kp. Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - 4 + + + 4 + + + + + + 0 + 0 + - - - - - 0 - 0 - - - - Qt::StrongFocus - - - - - - Link Roll and Pitch - - - - - - - Qt::Horizontal - - - QSizePolicy::MinimumExpanding - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - Reset all values to GCS defaults - - - - - - Default - - - - button:default - buttongroup:2 - - - - - + + Qt::StrongFocus + + + + + + Link Roll and Pitch + + - + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 497 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + Reset all values to GCS defaults + + + + + + Default + + + + button:default + buttongroup:2 + + + + + @@ -6846,9 +6838,9 @@ border-radius: 5; - + - Expert + Advanced @@ -6934,8 +6926,8 @@ border-radius: 5; 0 0 - 632 - 823 + 762 + 727 @@ -6953,7 +6945,7 @@ border-radius: 5; 0 - 230 + 210 @@ -7485,76 +7477,72 @@ border-radius: 5; false - - - - - 4 + + + 4 + + + + + - - - - - - - Link Roll and Pitch - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:4 - - - - - + + Link Roll and Pitch + + - + + + + Qt::Horizontal + + + + 497 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:4 + + + + + @@ -7565,7 +7553,7 @@ border-radius: 5; 0 - 151 + 140 @@ -7996,30 +7984,14 @@ border-radius: 5; true + + 0 + 2 - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - + + 0 @@ -8041,9 +8013,6 @@ border-radius: 5; Qt::StrongFocus - - - @@ -8056,7 +8025,7 @@ border-radius: 5; objname:StabilizationSettings - fieldname:RollRatePID + fieldname:PitchRatePID element:Kd haslimits:no scale:1 @@ -8065,6 +8034,575 @@ border-radius: 5; + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + @@ -9415,114 +9953,6 @@ border-radius: 5; - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - - - - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - @@ -9571,6 +10001,22 @@ Then lower the value by 20% or so. + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 150 + 13 + + + + @@ -9650,8 +10096,103 @@ value as the Kp. - - + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. +Then lower the value by 20% or so. + + + + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + Qt::Horizontal @@ -9660,740 +10201,12 @@ value as the Kp. - 60 - 13 + 10 + 10 - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 50 - 0 - - - - - 16777215 - 16777215 - - - - - - - ILimit - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:4,20 - - - - @@ -10411,7 +10224,7 @@ border-radius: 5; 0 - 210 + 170 @@ -10946,76 +10759,72 @@ border-radius: 5; false - - - - - 6 + + + 4 + + + + + - - - - - - - Link Roll and Pitch - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:5 - - - - - + + Link Roll and Pitch + + - + + + + Qt::Horizontal + + + + 497 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:5 + + + + + @@ -11026,7 +10835,7 @@ border-radius: 5; 0 - 131 + 110 @@ -11457,146 +11266,11 @@ border-radius: 5; true - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - + + 0 + + + Qt::Horizontal @@ -11605,155 +11279,14 @@ border-radius: 5; - 10 - 10 + 150 + 13 - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:ILimit - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 50 - 0 - - - - - 16777215 - 16777215 - - - - - - - ILimit - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - + + 0 @@ -12295,7 +11828,7 @@ color: rgb(255, 255, 255); border-radius: 5; - Yaw + Roll Qt::AlignCenter @@ -12852,40 +12385,8 @@ border-radius: 5; - - - - Qt::Horizontal - - - QSizePolicy::Preferred - - - - 60 - 13 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - + + 0 @@ -13427,13 +12928,211 @@ color: rgb(255, 255, 255); border-radius: 5; - Roll + Yaw Qt::AlignCenter + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 13 + 13 + + + + @@ -13491,14 +13190,74 @@ border-radius: 5; - 10 - 10 + 13 + 13 - - + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Ki + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 13 + 13 + + + + + + 0 @@ -13532,127 +13291,11 @@ border-radius: 5; 0.100000000000000 - - - objname:StabilizationSettings - fieldname:RollPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:ILimit - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 2 - - - 0.100000000000000 - objname:StabilizationSettings fieldname:YawPI - element:ILimit + element:Ki haslimits:no scale:1 buttongroup:5,20 @@ -13677,7 +13320,7 @@ border-radius: 5; 0 - 230 + 190 @@ -14206,69 +13849,65 @@ border-radius: 5; Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - 6 + + + 4 + + + + + Qt::Horizontal - - - - Qt::Horizontal - - - QSizePolicy::Expanding - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:6 - - - - - + + QSizePolicy::Expanding + + + + 632 + 20 + + + - + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:6 + + + + + @@ -14279,7 +13918,7 @@ border-radius: 5; 0 - 160 + 140 @@ -14710,6 +14349,9 @@ border-radius: 5; true + + 0 + 0 @@ -16216,7 +15858,7 @@ border-radius: 5; - 60 + 140 16 @@ -16952,10 +16594,5651 @@ border-radius: 5; + + + + Qt::Vertical + + + + 20 + 200 + + + + + + + + + + + + + Expert + + + + 12 + + + 0 + + + + + + + + + + 255 + 255 + 255 + + + + + + + 240 + 240 + 240 + + + + + + + + + 255 + 255 + 255 + + + + + + + 240 + 240 + 240 + + + + + + + + + 240 + 240 + 240 + + + + + + + 240 + 240 + 240 + + + + + + + + QFrame::NoFrame + + + QFrame::Plain + + + true + + + + + 0 + 0 + 762 + 727 + + + + + + + + 0 + 0 + + + + + 0 + 150 + + + + false + + + Weak Leveling + + + + 4 + + + + + Qt::Horizontal + + + + 632 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:10 + + + + + + + + + 0 + 60 + + + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + + + 69 + 69 + 69 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 69 + 69 + 69 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + + + 125 + 125 + 125 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 125 + 125 + 125 + + + + + + + 125 + 125 + 125 + + + + + + + 0 + 0 + 0 + + + + + + + + + + + true + + + + + + + 0 + 0 + + + + + 220 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Weak Leveling Kp ((deg/s)/deg) + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 220 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Weak Leveling Rate (deg/s) + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 91 + 11 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 2 + + + 0.010000000000000 + + + 360.000000000000000 + + + 0.010000000000000 + + + + objname:StabilizationSettings + fieldname:WeakLevelingKp + haslimits:no + scale:1 + buttongroup:10 + + + + + + + + Qt::Horizontal + + + + 40 + 11 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1.000000000000000 + + + 360.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaxWeakLevelingRate + haslimits:no + scale:1 + buttongroup:10 + + + + + + + + Qt::Horizontal + + + + 40 + 11 + + + + + + + + + + + + + + + 0 + 0 + + + + + 0 + 160 + + + + false + + + Axis Lock + + + + 4 + + + + + Qt::Horizontal + + + + 632 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:11 + + + + + + + + + 0 + 64 + + + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + + + 69 + 69 + 69 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 69 + 69 + 69 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + + + 125 + 125 + 125 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 125 + 125 + 125 + + + + + + + 125 + 125 + 125 + + + + + + + 0 + 0 + 0 + + + + + + + + + + + true + + + + + + + 0 + 0 + + + + + 220 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Max Axis Lock (deg) + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 220 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Max Axis Lock Rate (deg/s) + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 91 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 0.000000000000000 + + + 360.000000000000000 + + + 1.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaxAxisLock + haslimits:no + scale:1 + buttongroup:11 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 0 + + + 1.000000000000000 + + + 360.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaxAxisLockRate + haslimits:no + scale:1 + buttongroup:11 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + + + 0 + 0 + + + + + 0 + 180 + + + + Ilimits + + + + 4 + + + + + Qt::Horizontal + + + + 632 + 20 + + + + + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:13 + + + + + + + + + 0 + 100 + + + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + + + 69 + 69 + 69 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 69 + 69 + 69 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + + + 125 + 125 + 125 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 125 + 125 + 125 + + + + + + + 125 + 125 + 125 + + + + + + + 0 + 0 + 0 + + + + + + + + + + + true + + + + 0 + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:13 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:13 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:YawPI + element:ILimit + haslimits:no + scale:1 + buttongroup:13 + + + + + + + + + 0 + 0 + + + + + 91 + 0 + + + + + 16777215 + 16777215 + + + + + + + ILimit Attitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:ILimit + haslimits:no + scale:1 + buttongroup:13 + + + + + + + + Qt::Horizontal + + + + 20 + 20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 91 + 13 + + + + + + + + + 0 + 0 + + + + + 91 + 0 + + + + + 16777215 + 16777215 + + + + + + + ILimit Rate + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:ILimit + haslimits:no + scale:1 + buttongroup:13 + + + + + + + + Qt::Horizontal + + + + 20 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:13 + + + + + + + + Qt::Horizontal + + + + 20 + 20 + + + + + + + + Qt::Horizontal + + + + 1 + 20 + + + + + + + + + + - + 0 0 @@ -17495,69 +22778,62 @@ border-radius: 5; Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - + - - - 6 + + + Qt::Horizontal - - - - Qt::Horizontal - - - QSizePolicy::Expanding - - - - 459 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:8 - - - - - + + QSizePolicy::Expanding + + + + 619 + 20 + + + - + + + + + 0 + 0 + + + + + 81 + 25 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:8 + + + + + @@ -17568,7 +22844,7 @@ border-radius: 5; 0 - 70 + 60 @@ -18004,8 +23280,86 @@ border-radius: 5; true - - + + + + + Qt::Horizontal + + + + 20 + 20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 91 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + The proportional term for the accelerometer, the higher this term the more weight the accel is given + + + + + + 3 + + + 1000000.000000000000000 + + + 0.010000000000000 + + + + objname:AttitudeSettings + fieldname:AccelKp + haslimits:no + scale:1 + buttongroup:8,10 + + + + + @@ -18555,7 +23909,7 @@ border-radius: 5; - + @@ -19105,8 +24459,8 @@ border-radius: 5; - - + + 0 @@ -19116,6 +24470,68 @@ border-radius: 5; 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + GyroTau is a gyro filter, the higher the factor the more filtering is applied to the gyros + + + + + + 3 + + + 1000000.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:GyroTau + haslimits:no + scale:1 + buttongroup:8,10 + + + + + + + + Qt::Horizontal + + + + 20 + 20 + + + + + + + + + 0 + 0 + + + + + 90 16 @@ -19655,115 +25071,17 @@ border-radius: 5; - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - GyroTau is a gyro filter, the higher the factor the more filtering is applied to the gyros - - - - - - 3 - - - 1000000.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:GyroTau - haslimits:no - scale:1 - buttongroup:8,10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - The proportional term for the accelerometer, the higher this term the more weight the accel is given - - - - - - 3 - - - 1000000.000000000000000 - - - 0.010000000000000 - - - - objname:AttitudeSettings - fieldname:AccelKp - haslimits:no - scale:1 - buttongroup:8,10 - - - - - + - + 0 0 - 0 + 90 22 @@ -19797,2789 +25115,30 @@ border-radius: 5; fieldname:AccelKi haslimits:no scale:1 - buttongroup:8,10 + buttongroup:8 + + + + Qt::Horizontal + + + + 20 + 20 + + + + - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - Advanced - - - - 12 - - - 0 - - - - - - - - - - 255 - 255 - 255 - - - - - - - 240 - 240 - 240 - - - - - - - - - 255 - 255 - 255 - - - - - - - 240 - 240 - 240 - - - - - - - - - 240 - 240 - 240 - - - - - - - 240 - 240 - 240 - - - - - - - - QFrame::NoFrame - - - QFrame::Plain - - - true - - - - - 0 - 0 - 647 - 761 - - - - - - - - 0 - 100 - - - - false - - - Weak Leveling - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:10 - - - - - - - - - - Qt::Horizontal - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 1.000000000000000 - - - 360.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaxWeakLevelingRate - haslimits:no - scale:1 - buttongroup:10 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 2 - - - 0.010000000000000 - - - 360.000000000000000 - - - 0.010000000000000 - - - - objname:StabilizationSettings - fieldname:WeakLevelingKp - haslimits:no - scale:1 - buttongroup:10 - - - - - - - - - 0 - 0 - - - - - 220 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Weak Leveling Kp ((deg/s)/deg) - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 220 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Weak Leveling Rate (deg/s) - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - - - 0 - 100 - - - - false - - - Axis Lock - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:11 - - - - - - - - - - Qt::Horizontal - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 220 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Max Axis Lock Rate (deg/s) - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 0.000000000000000 - - - 360.000000000000000 - - - 1.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaxAxisLock - haslimits:no - scale:1 - buttongroup:11 - - - - - - - - - 0 - 0 - - - - - 220 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Max Axis Lock (deg) - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - 0 - - - 1.000000000000000 - - - 360.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaxAxisLockRate - haslimits:no - scale:1 - buttongroup:11 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - From 17bcdb61132a9fe9b339164626430a8e36ef941e Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sat, 4 Aug 2012 23:03:56 -0700 Subject: [PATCH 188/543] resized the default buttons areas, moved the entire sensor tuning to expert, fixed apply layout spacing --- ground/openpilotgcs/src/plugins/config/stabilization.ui | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index e91732607..34a811237 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -483,7 +483,7 @@ QTabWidget::Rounded - 1 + 0 false @@ -25751,6 +25751,9 @@ automatically every 300ms, which will help for fast tuning. Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + 4 + 0 From 56dfed2e8b5c25f582c8614d0dedc6115d7f782f Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sun, 5 Aug 2012 12:41:19 -0700 Subject: [PATCH 189/543] pre-spinner value align shift --- .../src/plugins/config/stabilization.ui | 27 ++++++++++--------- 1 file changed, 15 insertions(+), 12 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 34a811237..10005aa98 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,8 +6,8 @@ 0 0 - 792 - 828 + 727 + 704 @@ -594,8 +594,8 @@ 0 0 - 762 - 727 + 697 + 603 @@ -628,6 +628,9 @@ Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + false + 4 @@ -6926,8 +6929,8 @@ border-radius: 5; 0 0 - 762 - 727 + 697 + 603 @@ -8709,7 +8712,7 @@ value as the Kp. - 0 + 85 22 @@ -9963,7 +9966,7 @@ border-radius: 5; - 0 + 85 22 @@ -10106,7 +10109,7 @@ value as the Kp. - 0 + 85 22 @@ -16704,8 +16707,8 @@ border-radius: 5; 0 0 - 762 - 727 + 682 + 697 @@ -19863,7 +19866,7 @@ border-radius: 5; - Ilimits + Integral Limits From bcb23bb7795af35151f139b47454ce235d5e1e8f Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sun, 5 Aug 2012 12:44:36 -0700 Subject: [PATCH 190/543] pre-spinner value align shift --- .../src/plugins/config/stabilization.ui | 114 ++++++++++++++++++ 1 file changed, 114 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 10005aa98..789b72415 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -8019,6 +8019,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 6 @@ -8636,6 +8639,9 @@ value as the Kp. + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 5 @@ -8684,6 +8690,9 @@ value as the Kp. + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 5 @@ -8734,6 +8743,9 @@ You can usually go for higher values for Yaw factors. + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 5 @@ -8781,6 +8793,9 @@ You can usually go for higher values for Yaw factors. + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 6 @@ -9986,6 +10001,9 @@ Then lower the value by 20% or so. + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 5 @@ -10050,6 +10068,9 @@ value as the Kp. + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 5 @@ -10129,6 +10150,9 @@ Then lower the value by 20% or so. + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 5 @@ -10176,6 +10200,9 @@ Then lower the value by 20% or so. + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 6 @@ -12992,6 +13019,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 3 @@ -13036,6 +13066,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 3 @@ -13083,6 +13116,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 3 @@ -13165,6 +13201,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 3 @@ -13225,6 +13264,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 3 @@ -13288,6 +13330,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 3 @@ -14384,6 +14429,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 0 @@ -14464,6 +14512,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 0 @@ -14530,6 +14581,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 0 @@ -14580,6 +14634,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 0 @@ -14626,6 +14683,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 0 @@ -15830,6 +15890,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 0 @@ -16446,6 +16509,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 0 @@ -16496,6 +16562,12 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + 0 @@ -16545,6 +16617,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 0 @@ -18173,6 +18248,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 2 @@ -18238,6 +18316,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 0 @@ -19741,6 +19822,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 0 @@ -19809,6 +19893,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 0 @@ -20193,6 +20280,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 4 @@ -20243,6 +20333,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 4 @@ -21393,6 +21486,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 2 @@ -21468,6 +21564,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 2 @@ -21575,6 +21674,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 2 @@ -22185,6 +22287,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 4 @@ -23342,6 +23447,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 3 @@ -24491,6 +24599,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 3 @@ -25103,6 +25214,9 @@ border-radius: 5; + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + 5 From c600014f2f1514a08db6853857298df06bba5c8c Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Sun, 5 Aug 2012 14:04:42 -0700 Subject: [PATCH 191/543] merged the weak leveling and axis lock to same group --- .../src/plugins/config/stabilization.ui | 3864 ++++++++--------- 1 file changed, 1775 insertions(+), 2089 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 789b72415..783e4ee2a 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,8 +6,8 @@ 0 0 - 727 - 704 + 942 + 703 @@ -594,8 +594,8 @@ 0 0 - 697 - 603 + 912 + 602 @@ -6929,8 +6929,8 @@ border-radius: 5; 0 0 - 697 - 603 + 912 + 602 @@ -16782,8 +16782,8 @@ border-radius: 5; 0 0 - 682 - 697 + 912 + 602 @@ -16805,7 +16805,7 @@ border-radius: 5; false - Weak Leveling + Weak Leveling / Axis Lock @@ -17102,9 +17102,35 @@ border-radius: 5; true - - - + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + 0 @@ -17113,543 +17139,51 @@ border-radius: 5; - 220 - 16 + 25 + 22 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - + + + 175 + 22 + - - - 75 - true - + + Qt::StrongFocus - - false + + - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Weak Leveling Kp ((deg/s)/deg) + - Qt::AlignCenter + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 0.000000000000000 + + + 360.000000000000000 + + + 1.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaxAxisLock + haslimits:no + scale:1 + buttongroup:10 + @@ -17663,10 +17197,16 @@ border-radius: 5; - 220 + 144 16 + + + 175 + 16777215 + + @@ -18196,7 +17736,563 @@ color: rgb(255, 255, 255); border-radius: 5; - Weak Leveling Rate (deg/s) + Weak Leveling Rate + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 144 + 16 + + + + + 175 + 16777215 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Max Axis Lock Qt::AlignCenter @@ -18213,7 +18309,7 @@ border-radius: 5; - 91 + 90 11 @@ -18229,13 +18325,13 @@ border-radius: 5; - 0 + 5 22 - 16777215 + 175 22 @@ -18274,19 +18370,6 @@ border-radius: 5; - - - - Qt::Horizontal - - - - 40 - 11 - - - - @@ -18297,13 +18380,13 @@ border-radius: 5; - 0 + 25 22 - 16777215 + 175 22 @@ -18342,1529 +18425,7 @@ border-radius: 5; - - - - Qt::Horizontal - - - - 40 - 11 - - - - - - - - - - - - - - - 0 - 0 - - - - - 0 - 160 - - - - false - - - Axis Lock - - - - 4 - - - - - Qt::Horizontal - - - - 632 - 20 - - - - - - - - - 0 - 0 - - - - - 81 - 25 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:11 - - - - - - - - - 0 - 64 - - - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 125 - 125 - 125 - - - - - - - 166 - 166 - 166 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - - - 69 - 69 - 69 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 125 - 125 - 125 - - - - - - - 166 - 166 - 166 - - - - - - - 69 - 69 - 69 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - - - 125 - 125 - 125 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 125 - 125 - 125 - - - - - - - 166 - 166 - 166 - - - - - - - 125 - 125 - 125 - - - - - - - 125 - 125 - 125 - - - - - - - 0 - 0 - 0 - - - - - - - - - - - true - - - - - - - 0 - 0 - - - - - 220 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Max Axis Lock (deg) - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 220 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Max Axis Lock Rate (deg/s) - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 91 - 20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 0.000000000000000 - - - 360.000000000000000 - - - 1.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaxAxisLock - haslimits:no - scale:1 - buttongroup:11 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - + @@ -19874,13 +18435,13 @@ border-radius: 5; - 0 + 25 22 - 16777215 + 175 22 @@ -19914,13 +18475,1138 @@ border-radius: 5; fieldname:MaxAxisLockRate haslimits:no scale:1 - buttongroup:11 + buttongroup:10 - - + + + + + 0 + 0 + + + + + 144 + 16 + + + + + 175 + 16777215 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Max Axis Lock Rate + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 144 + 16 + + + + + 175 + 16777215 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Weak Leveling Kp + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + Qt::Horizontal From 89a8b054224ca3960b49a53ea829d01d4019ecbd Mon Sep 17 00:00:00 2001 From: Chris Pember Date: Mon, 6 Aug 2012 10:32:01 -0700 Subject: [PATCH 192/543] fixed tab order, a little spacing tweak onadvanced page --- .../src/plugins/config/stabilization.ui | 39 ++++++++++++++----- 1 file changed, 30 insertions(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 783e4ee2a..d0bc5a6d2 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -25749,8 +25749,10 @@ Useful if you have accidentally changed some settings. - scrollArea - checkBox_7 + stabilizationReloadBoardData_6 + saveStabilizationToRAM_6 + saveStabilizationToSD_6 + pushButton_23 pushButton_20 horizontalSlider_76 spinBox_7 @@ -25764,7 +25766,6 @@ Useful if you have accidentally changed some settings. spinBox_9 horizontalSlider_81 spinBox_10 - checkBox_8 pushButton_22 horizontalSlider_82 spinBox_13 @@ -25778,11 +25779,9 @@ Useful if you have accidentally changed some settings. spinBox_19 horizontalSlider_87 spinBox_20 - stabilizationReloadBoardData_6 - saveStabilizationToRAM_6 - saveStabilizationToSD_6 - scrollArea_2 - checkBox_3 + lowThrottleZeroIntegral_8 + checkBox_7 + checkBox_8 pushButton_4 RateRollKp_2 RatePitchKp @@ -25793,7 +25792,7 @@ Useful if you have accidentally changed some settings. RollRateKd PitchRateKd YawRateKd - checkBox_2 + scrollArea pushButton_2 AttitudeRollKp AttitudePitchKp_2 @@ -25811,6 +25810,28 @@ Useful if you have accidentally changed some settings. rateRollILimit_3 ratePitchILimit_4 rateYawILimit_3 + checkBox_3 + checkBox_2 + pushButton_6 + WeakLevelingKp + WeakLevelingRate + MaAxisLock + MaxAxisLockRate + pushButton_9 + RateRollILimit_2 + RatePitchILimit + RateYawILimit + AttitudeRollILimit + AttitudePitchILimit_2 + AttitudeYawILimit + pushButton_5 + GyroTau + AccelKp + AccelKi + realTimeUpdates_6 + scrollArea_3 + tabWidget + scrollArea_2 From 9d707cef5bee63e7a3f484551b5fb2b50294622c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 24 Feb 2011 03:35:19 -0600 Subject: [PATCH 193/543] Initial import of my androidgcs framework --- androidgcs/AndroidManifest.xml | 18 + androidgcs/bin/OpieMobi.apk | Bin 0 -> 148198 bytes androidgcs/bin/classes.dex | Bin 0 -> 12640 bytes .../ObjBrowserExpandableListAdapter.class | Bin 0 -> 3092 bytes .../openpilot/androidgcs/ObjectBrowser.class | Bin 0 -> 951 bytes .../bin/org/openpilot/androidgcs/R$attr.class | Bin 0 -> 358 bytes .../org/openpilot/androidgcs/R$color.class | Bin 0 -> 447 bytes .../org/openpilot/androidgcs/R$drawable.class | Bin 0 -> 418 bytes .../bin/org/openpilot/androidgcs/R$id.class | Bin 0 -> 403 bytes .../org/openpilot/androidgcs/R$layout.class | Bin 0 -> 449 bytes .../org/openpilot/androidgcs/R$string.class | Bin 0 -> 445 bytes .../bin/org/openpilot/androidgcs/R.class | Bin 0 -> 627 bytes .../org/openpilot/uavtalk/UAVDataObject.class | Bin 0 -> 1127 bytes .../org/openpilot/uavtalk/UAVMetaObject.class | Bin 0 -> 1440 bytes .../uavtalk/UAVObject$AccessMode.class | Bin 0 -> 1199 bytes .../uavtalk/UAVObject$UpdateMode.class | Bin 0 -> 1333 bytes .../bin/org/openpilot/uavtalk/UAVObject.class | Bin 0 -> 2255 bytes .../openpilot/uavtalk/UAVObjectManager.class | Bin 0 -> 5422 bytes androidgcs/bin/resources.ap_ | Bin 0 -> 140460 bytes androidgcs/default.properties | 11 + .../gen/org/openpilot/androidgcs/R.java | 31 ++ androidgcs/proguard.cfg | 36 ++ androidgcs/res/drawable-hdpi/icon.png | Bin 0 -> 48558 bytes androidgcs/res/drawable-ldpi/icon.png | Bin 0 -> 48558 bytes androidgcs/res/drawable-mdpi/icon.png | Bin 0 -> 48558 bytes androidgcs/res/layout/main.xml | 12 + androidgcs/res/layout/objectbrowser.xml | 8 + androidgcs/res/values/strings.xml | 7 + .../ObjBrowserExpandableListAdapter.java | 99 ++++++ .../openpilot/androidgcs/ObjectBrowser.java | 21 ++ .../org/openpilot/uavtalk/UAVDataObject.java | 27 ++ .../org/openpilot/uavtalk/UAVMetaObject.java | 50 +++ .../src/org/openpilot/uavtalk/UAVObject.java | 117 ++++++ .../openpilot/uavtalk/UAVObjectManager.java | 332 ++++++++++++++++++ 34 files changed, 769 insertions(+) create mode 100644 androidgcs/AndroidManifest.xml create mode 100644 androidgcs/bin/OpieMobi.apk create mode 100644 androidgcs/bin/classes.dex create mode 100644 androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/ObjectBrowser.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$attr.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$color.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$drawable.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$id.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$layout.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$string.class create mode 100644 androidgcs/bin/org/openpilot/androidgcs/R.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject$AccessMode.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject.class create mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class create mode 100644 androidgcs/bin/resources.ap_ create mode 100644 androidgcs/default.properties create mode 100644 androidgcs/gen/org/openpilot/androidgcs/R.java create mode 100644 androidgcs/proguard.cfg create mode 100644 androidgcs/res/drawable-hdpi/icon.png create mode 100644 androidgcs/res/drawable-ldpi/icon.png create mode 100644 androidgcs/res/drawable-mdpi/icon.png create mode 100644 androidgcs/res/layout/main.xml create mode 100644 androidgcs/res/layout/objectbrowser.xml create mode 100644 androidgcs/res/values/strings.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVObject.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml new file mode 100644 index 000000000..83d19e96c --- /dev/null +++ b/androidgcs/AndroidManifest.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + \ No newline at end of file diff --git a/androidgcs/bin/OpieMobi.apk b/androidgcs/bin/OpieMobi.apk new file mode 100644 index 0000000000000000000000000000000000000000..87a15c5e83805a3bb48265a78f9bd9154813cd35 GIT binary patch literal 148198 zcmdqJcRber+c%D=GpSBd$sSoHMD|P~*@W!ujL4qZL_{``5gA$8n?f>^oy_dLcgF8{ z)8~7Auj_YT*ZsKfe}0e0@2s5rn#a0l+__qfE1~!J3 zfi;Vnj-!RG4a+kfV{>MQXJ&`Z7#Kcp@?`3S(V|9q*+jGt7#YxG=NLkRJa15-{psG* z;`{sIaECl2OmF-qFTX<7{R68#t-$K>gE)@ip_u-j;rkDZhQg%iiDL?Lhpyr5-sV0< zz>0(8fMYRAW>e(ZQYe@6kp0b<2?l{7c_Dd$&sxS_Z1n2y$qEZ;4`R&yE}OKvC5cDb zuS{-Sc9?ga?Jm2KZJR@-onhMN7F^JsI7yM1^TT(=bm-E#$`6@t?GXcxQW4|PNr7Hu zU!A4*m7|ubN&51N9*Ngqjd|fN`&`E`zk1wJ_l32tu0r2RmwT@4%l$VjYwFhpd)01i zwpm|!ZY$-GdsmiYDG<((d@kH%2&K3?9jAW!1* zaK9^fqV=`h@}z|6iDNBmn1tPgE~g4T?60Z|O4Yp+bLJ}Gb9VNizNHr0QO!nUtCXv^ zTzTfg7skfVc$MzlDI%@gV8GWU%me1E023Jr>@QzEoo1EpX?XiFD`s@J7M%(rH2Y- zS65D~?4F^mUs6?FJO6Nw-};3L&1z;Qy^Kw%CLE44J&yTtt7~R>0?V%o1Xu$I_j@EArvYg}67Yl$PmEShxxy4@2IRQg?)Bz*jTU?kQbtc~9l**1>flM)Ty6M62kelIQ%)25z+Fz<~0y#GXLUT+68@@P^ z4W7C9nVcJ&X9v&KJz?}}I*IW){?oa_7pmQJM@e?h6Hlo2X6!K#63>Xn6g$>`GPRjXD-_ozF}|oq2Tpde3Gr$a?JE zuBPEX_u=wU_ayo6KAJHy>mZBYThq3a`LBOpT$z^-X-nW9!b`Y!mCK_-Oe#pgfV|GI z@=Uj@XVKduRFP-&v2YU%Yg~Y6-K_n|&-Bbb&JMj%iM*FP-M9-`4l_Pv6;^D9#~?da6XD zu=sxaQq{A?8Go%(S2wn^4?8y-qtBz8h)$_dMrsz%7T2ex2?dr{&}^;bo*E81J$``muS!_ToMWt7JX|l$a2+L4v~MyNZ&}_>XSB?q{?;?4@$I{^ z+f{SMAKIIH9khGeaom)rSh1i$%>kFE|g%BojE6^*mjaE5?f!N&g(Gj6bY0 z{H(njtkpMfd#cJrqbXPUyWCp#!-R*f*;YcdBN;ANQ){C}I4N(zGY0Ov%r zagQx!8`#W=b?>hF(;#;6yl|q~7PeM;2G-0vR@Qo07B(cEa-l{FWb{#28i>1{l^DEExLmP6xvtp1K%j@ZBx=S0Cd!hA~_-#?ZsC zz%a*PhR^00MsWZCbllErtz@>=}GAJ|39^yf=f9k^VQo zw19b;z`XR}K3({Y1z@bzKX2d_84D3SIpHY^ z&&TjIho?6@v7wa{eL&v-BY_wg=Z~e}e=TFkNS=bEm>o+1(ytCk#d8d8XjKQ=Fo1T? z!aL-;Hb~}E=)>l}e2eI%4)kmazdiGx`Z|#vEG#qz8m_@|A3u=Kgzyeb%gJ|e0Tb&E z#)E(R4zUrG@cfU5!@u5Q|Lfgc1(A6}7lJdxSs*Hg&-$Y-Q&WDSrx{nO|1d-(j%lC(;hmC!#n1^od;iU(NHM@BdHx{M#4V5j>E2B7MOt8N3|*BS*-0 z$etmOfA;O4@BZI%bn?6Z`Y+Np;-ld85^@bevj5@l^zQ%8$IZvUK%T^K6+yE4Ryy`N zx@HEqp6Wk0W-->YFlT;lZsac~BYqy27`gSl!~;zu-7rS6}IiZi2f z)8Fo&=KnJw&=hI3Eg^&DasAVqm&B;kWlfw*`I9$Piw#84 zEXvEHV&A^~c>UmYiaL)yaxW{b>&;m{xb_ZT6}e`0{Xn==g;teY`}pdI{m?_{&Wq5l zjHoEmZvMl)_!RN$w9kW(>rd2POYHflP}tho?9?hF_Zvz$iFIE3eipgfnqG1}dv0ci zTVUMhQ$~hy(D1-+YV=)a$HxkPc7yCX zm`%Ll#-<<6^EhslO_a{aML$&1y1=41+S^^6`Nohp^%v9&i;<0E`_BBFm+iRy+h47!=U+6w z6hjvMiiFe4ETmUTx?4*#Gf&-)gj{UASH4XkJ!0IRzxQt03m*|2T!}x8$M8^B%|KlI zo9k>HjrYwaMDa0nhtCWx%bxpvYvS0Z++OxtGV&Io;^5#gkl@Xcbz`PNenrWNO*?64 zW3y4EjbZT~5BaIE2J5?JcZzV~-iyZ{_a8G#i0SDiODfb{KNEx8B&@OWu$fiDB=zs_ zEgzV0N;K1+L$3MpmC;G?OdxMDEa_j098ba?QOo>?!r}O#NgDMUZb2(Z_RO0CNBj+~XVEPn!P!`jQ+9*;R~_abox! zi@Wgg)G+?KmBXhu9-Z2DraEu!OF@iJTA_qU#M$&dwyqid~Ru}wfT5*NxF=ZGdFX!$BACb9* zg-6cL6?O|hzZ5DQ@4tIML`1{~3zu<{=H}*Czxtjp4e~r2ER|neT;z3JyH0-@0}+qW z_0|}6@$EtDVA2cXt(B?wUS61eXFn`2E`BE27vp$iDE_!};0-y9zb;=YpQpCU9(_ba zOx$UjTa{`*>?j@<78Yl7B5)Gri^T(lX8rl44%sv`G<$UvhlwS_PLf)=QDGO4XF1l_ z`9ZSCX>+dBc?cHMX}yhWb1K$iZ3g$a1+?2#YfN&k+rj*8KIsh+DJiL$%|7kE%-rhc zM+z8z&!+|l2Px1X=~20#KFMv5xYaOSk<^%elJ|IG)uHhDZ;{upUuTq*LLDYi`oF>_$OI4_#@p^Du31tm8rHwr7_NfBg9IhUX5pgoMOfA-8JW zbLV=xy6W~sPKL#|wzg)oJ!JoFv;51s5LngTUS-v6Wn_E4Jb5FBLD?!L3SMSXwaTeT zicV00Wu~D{zw_1Qn;Z26vgs))-oo$`M1M!w3JVKo<}!2X`~oKIDvDspJfs)MxSzXs zh+v=ys=vceF7=ynW^0s%QZk3=5UCZL#Z<4qTTZX6j1$H{R9JZ9DTu6<7292nR1iaf zjUV@rW!LA7J&S!jYtibj0apoX2_4-ER|ZB7i#t0zQGc)G#KnIk+V>1g2?|AxA zs%Y9qkUPy#(bCiZ9ZR&J)YaEg1_lNurlyLHjyyUi_sq(xt4pHrZ!j`STol|%%qgF{ z@pp|BTPCeCU^^+PcT*emJ3lIAZuI23DsjfXKG~bk-RT(_uxr@(I555f&G^&DKhdK+7S`vM4u?<79!N-Z+`A}{LMs{h zce{36z}hV+U%SV2C19y^{KAlRyFk8LHa3>K$OCXJF1)D$4XKflR|K|x>NPhuQsN!& z<4RLBGjRooe|K-M*zB1Tdtg*DproZGgTCE5Ycp5k-|AD`6GNaW zEq$Kra0gw-idf=Vl93%>SbL8XBaj)*{7P0)MJ27cm~(P+^6%jC8g%p0KYn~gxst)g z#41j?~q!Umus-Wc-I> zA@d~^sgDf}y;M|G)HJ>dyN7(&af6Rf9X1f#BOo$5I^E*Myn6Z6TT{>sM9QDm&rmYY zr#9<%B9_c~xk}~2ORtko64BJd-FSjtuC*Ng6Z}3qJP(W zOb}0+uBW>jjh!m(=vWr-Fm@I(G$(@(NhvLT3^tgOH9IscZ1cyxi?hu)bFZI_h59}? zMye-b(QSq=Rs*!VqiXgIzye}n9`EkpVxyQf*PF& zY%6wbTk5Mani^0zf^Hm7P^qRb|ZVd5HES%E-uY+WGy`_UmPpznjwK zKl|QK^h&^e)84F(sOk;c>QBeg>@MQxQ268vmcUvg%|lsP`jd&KD!95hCq&WG}xfXV0E3KRWzlTX&wTkrnS`1(3FMiG0l~SH*_hjt(9^ct8mW z4G|0s=7@nsLsK`=51=+6DjA81?kDpv?T$4`9i~$Ikd`(dB2M1niF59+m;`*akr(C5 z?D@#@VpdYE!0;RZm?qkbQ>SLAWJ~#pngov7jWR=HvvS(Xm{%bYbRYlUIg7Dg!-F zA?R~O9yYSMwe>oxzOc-CdT#X_g^Ia3v(B-atq7(DP;2QM8qVc?BZp{^;N)vc(DK!< zh6S@XwRc}t?|fxxHsd5fAw5yLf(MO=iXy-s`yQd9mGP3?=|NLd(}|$?$$~8k45c&& zVf>h#{hHJhKs0-Oi*u*X6D|WQ|+s7aiXsUlkbu8Bn*XijqVaq7p+n={_^v$S`>|IgJ#6(m*&!^+=XsrW3IkKzZ zY*>%ilTd_mI3*=z=J!jAUcgXik5>{s1O^e13ks_gWmuq^sgm0(usui<+a^YNEWI-T zi%OGlnB^rU1IS-&$Q$VEqfe~n9;+r{DZitmBjWl%0dQz-2MGqG51_1;G;S5;M=j62$Oc6Jttsm@a4 z`TF{9Ts&I2h|edzGFWE)E8if1myb_LL!&k7G`nS(F=r;kQ=qoLN-PpQzfdL}%Xz9S z?6irA35psI5<44970Y7#mKQEuFge)U#Pt!maqHHkY6N>CC_I=CBwnl3V)4Mh_pR~7 zaF3Q(Q4vS!v9WzX*!4*6aYQul3q9iV|B+D zftyPKBfu^Sqjf$xt{d9g*@94!MRM?ztWGxn<|%Fw1P*so0y#+#L0~2(a9r)%{w-ai7SX85tR| z@lVh9<@Q0?t-G}eF`)5y!)spWtt@`>izHX2lK~cj=+8HX&=8Z7UPmJc;`6kmlvMX( z$p~{DD~bj$-tExw{Q2`=_vaTN@SkdnjexKrFc42>{|{w-)*VcJ(d|Rp^<#xPcB? z=Ani}TEVYhY9gpGm>7=N7YKzRB;U)d*}DlqEFjiqILsbKJvTQu)?rMzgvz)`rVt2tR_HMCW;~L6FR~1`>;zpLu%NtN7p#eic89 zb#iu|Ty@Yd88~b3iszk7TY``_I1@<8&>iocpZK{eOmeoi9Cy8&x@3iJ<@QOU6W)W} zB;hoJz&IbG6_oy~7%4hHDmMfKG@ZAXUbhUHdoVf+;bUS@5+l=+dB^+V%a^;JJEYL^ zUhvV*#e*)PgD|irD1Bn4$Df3Q1^3bc(4$V3iUtB^c^}j@+f8OaNOdeO#pXlJ>^sc) z!nxWtTIMC{VBoRYzJ`W|-f=s0Aro@dNRv(YJ62oksaAPV6Bz5w+{*W1^s<-g?}LK; zDzi?zKp~j5wq^xW6p0a0&Qy|?mS)4dcjf{qB{I)Zf|%Az?G_?Y<>kJ;&G`s0kPt_Sm8HGWAp+UEapOj3ynu757#L~yZB>O=5qFkN zAFA)YP*rTX!}CcyNg_VNXQpbl0`VOM{UH3{DmGvb(Deq$xQa}pz*Ild(#io74&wr> z2EoA(&@G#-1yw9e1S1S{#7;1oC^gqw+$`IT%{O?|#Hwx}eJdi<LqKz;mhX>%wjmKl!lq^g)X-WG7?hqi~2wk2El!z(ffzn zH7agyLU*M?geemRoVU^o3KYTnK+NgQro>fdSb!vbz_5S;TziTOYg^B0S}xx7dPL4- zp1^9NJ*sKyaPa80PH|KGK#KR;{N*^J5Q~*J*L#Vm^Rv~89v%mur%&JnAy;qLljqOn zKxZMy4ZI?g2dm!}FQ5)$*0Zz2ji?=^9T8nX+*cJw+f_AMj=`JInQxOzhtM~D>n7Fi z8%7SXTSLFq2}6)GJdYch32^Ygjl&^ zk*$TYwe#c(&-d|kXx`u9;#wEpV>Pj`Fp@mF#(L*Y3iu!hzB@Y=#LlJ7X>}MXf^Wp~ zaKAvtD@rMxb-DKQ;~E#EtrpD!wG5R)#w44VtR|n(ruU;e*L<+d1Okb6SX;7`6uMqK zRNXHnEql$Tnr39gE2+EWJby84ZIZ7pD8-KyYjIb*vDSW&mtj>@N^^tx1p*rV9MPn4I+4yCJxe@#uL;9IZ-IynyW44}A=I zOUyiLSDVMahlnI?iwTHixe156IK*T>WKd7)zWFPhdz%~tUY{s6W~VJbHKIw$HdBhT z#Kq`m2;pyoBDEsJHsY8z!&;OV7;b^}R(9M~rmkzYAmJdK0Fpiy7Cxd2^Os8%hGa7M zgS3M`+ot;Z-oh}XqN|e>yjiQKSeil~QA%1R=@YS47{a(z&c@GA=9JyrT5yWF)Oi_K zih*0OF~Ysk*}9x9f_vKh!>wJn2syj#*0a}sGp5jiL>GZXQ!_G*#2hRUHSWt?wT1=YcR=L|0mh1bzDpH&zuMyzvCu|-79(x`^~o1&uXDaqnLhL< z#R-^+ig4kx_77TJ zxfN2dg1g)PPR^Z7;`Y6z%5@nqnx3dIB!k0iAGBHj`wFg)&C2Lqz>d-YQy)r8(}pw3 zX=r4D>p`T6fPg6&!-sY2&|$CPj@`;-oNs6J+vDl$%nlYvw4C3Y&0e;;qMcD+&Vlqr z%c$+Eqwr)ukWe3!E!CIywygi=HiK=`_5@S4f}zod%ct0Pv&)MQ-YVIs@vNzZ z^B>*)z~mrT+**E7+Bm2|Vg6&eYGevOVs$4-Cc$;zQY(A_kP@sepWVWbt;K<})L2Mm z0#dm0kb*$+!4qu#i*_)Ur&d-90J`W9A(DT(7T0j0GUd(kp!0lzRAfL!1XpW*X@Nnz z@te%Ca}Tq2--E=m@hK2)yk?v+;4^n=F4D7Y(zFdwh}!=!SWv?tX?3?==3G^HsHyZ# zp&FVD$?8KHA1o*jNX10lRAJ*_4m@0WDRk`X@sk=F8VW7P#oqDR%a8}Z?5J%y5M{?x zQc<}{PcQDgwIEOVSat7=6_I{hwyf2>Lq=|%_aTc%868#aYj|=RoRFcQPjCr+Y5lUpzUGf+ zybuv>XIGakB=yF< zLPc( zM8A1tOC4@1XURb_2Ha6^wtA8Cwz;Pt+tAR^uS&;){DJ}w(_SX5GQ7WdabOV)xKMB^ zD3&r#l^5~6lf1%%tyZ4U+vnT2ZsWyh7U;LX%>;8YnNy{>l~u+@tIt3fE%$?uA%6bK zyDVdJTCTy&?%w6bkQ!mS*jTy4jf>JE<(Has!)_HQA9{FA=h}{9RX<{lvFX#aZ-T0T zSajw7T8mUvfPz-8N-UQ}@8{3%fOi}yG*iKUIr5V)4p*s%g=K|_FZj)KcqcenCuk*g z)4DO5K5S}@?DW@>j{Eu1e|$On?#8-H393es1E&9IX>P!vl2{zD*kSWx8>jvVPL)C87jlnXczZq$1^7kg6 zkqWEWx&ZE>S|gssz|IK2`M&0iZTf<0m%3$si{2#iGhM7*N96PrS9kY zdT#_~LoKTXB*w4+znRtwN?af@pjtK?GxAuNKCFg5o)im&Cha*yO6s3*r?2By6P!)@(v;yXvp(RdRBaLL zg>$g>uD|`QnoH|kPv)c@I}V=)=d)iaFaB)di{kOP?w2BA<;I51({qGoY4sZh#LLN`> zZ)U_IPCY05t7*ieqsyvY&8hlaYWormS3t4WIb0_$X5FfPsjsg;b545)>#lc4084c` zyU};FXkbiSTsKIu?O6R;kPWbSB4whG^7@#b{v(KtZ(=fOOQV+fE=rZJSHm9{s1>)W#gH-L?lxTBSgTBLandU_WXxLvcYaWPsX4MG z?(>CbU5u=Pi3MawqUfDB5W^#haM9=;7eRr8jjlkK`cI(0NNxduq`a0ExrYW)spx^M ze0#hAF&P;xVt)5hHwPtN+f`A938)qaHad-F>J&GJYA}c&VwHWgh{#;KqS__E)~|sp zgLiX6@1FZPo%Z<5iK#Q;BQNxKReD9V$jbw`bI`Jua5brpAVcgxp2zSdD(h z%+{`nryNV%se$4iFXRzGut_fnZZrF|Oe$Dg7a)NM;BrJ@Qel&~3R~=*N)~v|v#Dz0 zJ4Vx)dS)3LSY0V@*0g?k>0xdNN7)14{!{>foU1!sY|ktkm0YV7)N7LK%Z0)?J~%j$ z^LfhJn)l^Sknlf1@3;?{_aTu}nE$qJX<@c%Aql&>x;kup z*=<#>4b zoY=QDM>XH5O-W>T)2eTHcUb1**;!m1x^{~N{7jN=qWtM127|+r@cdD#{`@)pXjLf+ znd&e1cuVG^kd1+8PU$!$!zL)0W0dehnTqpffFwkW%22X&Q4r{{I7wbp-Eqk zW>($(`U3Qq$#uJ$>}o~6i2N0No`Bp})vxr6TjB?poR^$O8qUyvHyNw%-6pTF)D74- z3cl}lzK{;t7LA^grqI@x>cEt$jzO>d-p6RiN+vIi3D)$a?z_KM4AN(JdN_oCR>mX0Fbyo;{vSO7$W z%JwzTR&|T2ucu0=BzUc-0*4)^$pF_uF1U#mPoxY5^)ATdc7Y0CMq#6{32Plj{{h|_ zMC>&3bg}Ba8@R9-k93FLSzTd?_zT>!v~l-nvO3;QFg#8P_qlizU~a!*Tcl30m8Dps z+~>5U^KMri`_Q#>uWshN`8Ez2E2ph~qkcgO3KTXLWH?K%YMK8fgtHt8G$YilV!*+^OFKhM@$Oyp$ypH0|AqiJM+#9tFuTR2s(FBzV>X9os8 z9`>U-G@9Puf{mtMf5h(fqMHZh3KbOCVnf5OwOx!#N}>`t+F!@^2);%{^aIj{G*GUA z@JQ?&i-?-qThLn=2VG49%U#eAk`sjeDl6l|bc@8oZM?A7B{RVP6CZaxFPSR0M5@vk z&?r%jlzI*)84H~@HHir&uF2`99SH%PAhjjRT+ML1_{dRuYmpM=LJ3X{$Qn1f-s%*- z_+$5Mq#Ej${+?eFx0Z%7tDLuyh{(JoR*qTD#N;D5-9p=W<%d)Z-mBLqNP56+Uf#IS z9528!mBvhLn90oIgHxWe53aW31|?9TToUv0{ru}w4{#Z|hgp0C9b>K4#fn1TE-B89aq_IaHOS9T6!_)nJlwGp!gUsl;?rZM zld7E9pSsD3rZA_;2o)68RRafy$6zW?64Mb)`qbg=A#rh8b8{xo`tyAhP`En$Z~3d# zK{>;rXT!d%o%6M<`ZCe9&b=D6;o2}cUJd1Vp79nm%W~L;>6LOZ8w@L14 zK4D~HVtOPl{!&Ee*PDxw_>+IG`&du2CJIZiKYzNBm4Vl{iAhp7XQ50QkV95Ij~kuQ zYQ(DMTfLtvzDKuhO&{VDAjFExSFaL?5>)}JL!dWGBR?brABn)xsPwF?z>eDXkdTn1 zl$7g8W|S4pSt(h^NZ8#Nbd=oHek8Q^Zk9SYm`jw+PyX&ibhA1E&}-Cu}3wvtp(dO#=; zeyj)$401YmpESpDTZ#znHpy-PrAApWAy`?%xwf zVc%|ZuJl5$Pz7G_9YGSJn2OB*B+&QUMrM8_-NRmE1agE*_1a~Gj&K@;`MbSgf{ehC z(z}7(7TF<70>7mSFLyc_v)6CyHXZo+wM|cV_w?Y4L_-ei5>{$khGN==z1z0E(^QPn z9UdMD%7o8Q9R)Im-aYbGZq5jQ(WFGWAdBAm)e9h)2Kn?MXLTDUGBk;YwlyA+W;W?} zB4H4a8;v2Cl_v9U3|r}?s1!Yv zl6nMC11yKl+Jpq8n=Pr+en1+%=f@970>j)soG0N#V;k20{2Bc>68Z?FC!=6jQOM~6 z3kWedwNTa!^>mdc9Y}1dUd%UY4{MsDBM>brP>%nTd~9oPTF;$rX5&^rly&Y zs)-CL(|I;<%Lf+Yl&ixELh)|!}{oDS7m`d`Zg-d0*b@Ihb*2tG2qNA5BUL&!JR)M#U%UP*4U7t$37|o(Bso9GW!1Z_2XB~U&EJpF zjDg4&AN9UrX4q(AJ~-$d-Z@-c8!$kwOF~9@j~~g)CjleJSXWmBa#7=6f2f&M^F<8| z_Q}p6*3lGH3c6c&ssgsNoSRz>R9@K6Yz#ZqLLmpr9LxZvR&|m-r&NlMgj$Tcla`%l zW0DcMTTe2)BXl_~FerlsK*z_Noa#}xVMq<<B}nVDg@ zOZi?(M#coD2)xM@5a2PV!XNr<8Q>A1>NMTKnus0?^VugL7FzS&uN%srzSH>W=UE(l zqy0t_z|!Jh^N4+u_<(bj&&l;bTDs@`{QyLl^u7gI)*YOE8yl+xd^5Dp9d7RQqrKcC zYLsXeR9v1y(d?n5q@uaG`QX%>=x7GmJBYL_<$)0*JN+*lbY0R4(}VJT+`z8e1O+eg zJ;?bOuw@SzQ+0?D!EU~SsKY& zqC|bFs|6831b1q=yPyE~Dl4Z#E;=>HQ^c=*nq;Q)=NA=y>04p6x1)s7%3%lZh=)i7 z27a+TJ{q@Hcj5Cdz!-N$Cutd20A1Fbw_LO4u1mr4PbO$!hYWgMj1(qLe>8= zVSOK4%=`D$&whTo3;fq}n1mu4MA~j?4Hs*e)t!7=&5JD>T1oo1*m1t!|E5Q@w!Ur) ziPrYUWnlQoLAe~N(>B0XhIpvHjU&&n?QQ8FL!nOK*4~HY7!^wN7R(uPXLI07VB4&C z$H(zC=)xp`0|5l&F>0_RSD7INmUoJU@s6X+)`BCORMxR6aDiv&-mYmwR_YgqkDeZxxtc33>8MniTr_5|upV z5XGWRUVMhi$k6a(QIQfLYjChZ{jszGXbP1?JWCBiirp$k-Sh4jbBT#vp|7kd=tIXvTFs9%V1)iDzSn))=Ta3ZxfGtNwaP;@nZ%`Gj8fY~5F#Qhs) z#pdn#mb*-vpo#?YbTnZ!K2of-mEyypCC-}Nq{~q6Cn?_aO87Qw^AR`{0LeRI*o}aI zLJ`qd58USPu&}yVnm{^w`pu0l+4U!;^*&En)4zY0SsbcR`S9TbIQ+njJ|iOEOP4Mo z5rqsV^R>FWJIk@&hcfS+4l{X6)}!PLXs%ONqRB@Hl_)+Uq)NBA-Q8WMQI9hlSApv) zzrAp)pr3!7uXJqu0y%%9A)6l`f=0q*1+RsD1wx(#Sb{ixIn-?q5zGW%zC)pRhX<$D z5(LC3OXD&n2)^;XpL$wQP>^i$PC`j3g4}K2^2Kh8wz89xO%^6I3(IuB7k*+vK^Phx zweMPUIH`SjA1r!scC2HV1lQp6Q}jfHB2w8+ihQhMIPva*@7jYJWbS}PjV5!{&G*4voxMg4nMh&`YfPDysJq?m(7Fl;47WGS0f|J! z#5A34pw&4~B{-g&s*QN}{t`_@NBal$JAFv|xQS4k_kQ(Nr>a7yJInUm zr1Gl|f**5%)(??Hhkps7nmck&S+_Azqak(j%`x|Qn2ez9mSk4 ziTRs0!`Q8nCL4KND)f1Tw}9|k<&SuyIl)-e>hAwA<=w0hiYhS@(5WxmP7M%iXZBrX z>atD`x`nAa!z? zhr#|d;gRN7y>ctK1Ww|72y z@6VsjtpSTna7&O;vf_PLsbly63>=_3{6o!;xNMi62Wbvfj3(BHwu#^i+SE<^7ZcJ3D)k?pIuy!2|@Y)%u)+bY0@`uon0n z^JX`33yWOHNYO)C57Zw{fp{huvQ%w^!p_`Bf5t%|A`oe_y8$uq9|DD_3V3S3A&irP z-PeMG*lUVIFQkq}uaABZNCJbPbK<(+w)!28JAjG(UH`%p1fi(7_yz}u5)@wEMn^|? zCQ#s=ww?JwRki+|k1e+C1_MKMuWjHe69knIrj0eAOCLZ8*9k*SUOzoz)(aQ~2#78I z5W(O-XJ_M~J{rAScEg-Hkccb)KxjgUM4;WW9F!W0x8MB#5CXdoj?-jkXXp2ufkTd8 zQ~15UTL?AiXTz1M0J|YH`h87Jabe|momz=G*N=pqMtt18NhUK|KccC| zSQeuWgETr?6a2A(}+RLp}9jaz*Om?+? zlR`JXKcWrKe)CMZ2&fS^xo?w(d~4eKA{hl-7RU9ejN)Qt$mjNgyG-4;j}v^MW>Irc zeERfhfX9swmT2EXT>=g{nVO?KT1GdWlGk*W0lFavy};to;}eRA`pF3!ihl$#(Z@dn zrB5rBVd?_*`(bI@HwdHs(#H`l958~~{mb!y>a6zZi3h^V23i+nOF#=DLhCBGorknQ z28bwmu}cV&!~)9KCG6+dzQ^$-LnL>9@~R?0eqN^yhT|TCJ~vvH8I3UeOVf;b>V!V) zH3Qy2q^IES_k}Q#klPA*K-i4;;<^tkj-Fq?K0+b@wy<%2Q)agP;%P5lhm}MmLsz8M zAF@FW3^f^~s*DLyHpyP2d454b`Swl9y=MEql(j6>s-m zjnqp1{4@a~C>?=#Xn*K=-TAoa4E}GvNdQJc3YvdEM{4Ja)ikpc6DgqM$v`E%3294k z4A@6JuG9#J>$&ik)fF?F+xANuZSVM^2-u{#DB#>q`Pi$Qgm|an92ooLd>>M-em1~~a0vi& zKww6*Ba57+2F%yP}#$IQn<+-(SrJ2R65*keGKoP+a+iido_MJv>)I}OYHiDs7m zC-Aa>cJ>hcnNUJjHn`k48NB@RaMi*cJdjT52W;vSjnC*_IT#YZn6IR;$62gZi+ z4*STH90;D_XhEFUwNV>hC_LwaoPPw9d2nz5-5?$X4ilaY=rRl0qCn++6&8%bt9SmUSGE=n)IRE8uq za#q1JK?g`vK%A6^5G{y8NN{rgm&m_Z$-6FscGn{|TG`tHs00RFjHX5$2S=XQJS7F{Dt z6MD|ZHi_6f&wh0YK9jM69xPTBJ@jf3Fez5$&X||KL>TqvfCO;u?aIn?s8Yug_-!9u5W|kXLDQCd3F~k_4U31FbbFS4VtSfjov`3B6WC&e-fq(_ zu+6~CY~GnrXI?VDU2{~0_;cS0mhoG+ZfQJqzX%nz*d>m%v^48jT2QQL(t|cD4Kr$# z#$;vpjrN^H*@U{l?GRk$-@kt&$>kdoPLW*yZ~<=Kv~9Un!az-}+nF#9-eYf)#qF2} z!D~DBs8N4laIh8U^p5+rzA@nKf=XDf0T_Cs8;*7}tK5DgOCiL_C;{iSu*sh2>gsO9 zw7ZBQG~9fH78ka!>l?FOdr@w?R}aRn*8Bj5pBJxeZeI(EYLw_KI=<7h(%}BxHT~ouk*76|N73z1 ziCZRcKor1SgdOexYZfTTh@ISk)W4~&E_M2vUOB@kpG;a;xDcH@3UGojiSaOlqX0Jk z7~OZWh`#Z)S?dW1QVRXy-(y%?y%v%CbZ=u8+JiH>NEHp*Lp-M=|Cd$4dK>xACCr-T z`sID36cp|Lr+m;JEdqmStMR9x$%c0Ft=VyUI=a1-N1wMNnKeHm#X#gxt8DL=pNn=? zJ7WQRzc0F_!|bhV5~`gC&SMbP3IXw%!5ig3BW=b^FbAijF7AKIS3?dxLL@m?JYcQ} zC!JG-zQKZT259e#9PPIsnKi$|rp+iQV4q3-j72Ddi!^{aUiEUayz?HKs@Xtjetlh* z3h#ovynOk=*1+cedb{albA(`jNMUmFJ)whH+2bPNRb~xVCBZBTY!?gAS`id373*## zvGK4l9#wN+vKL|PC~|xhIS14(_$MopNp&o2Iz2bHZ{+A;WFC?Tp+n|e_nG1T{gu}~ znqqgUuwC>D7tcFtj$`9{y1Y30V%(L=NJHb5==B3+XA_Rn&GC)w1_AqyYc_Zp4)_|i zlOq`;i^^4BIIR5H@b>N7Nf2)`<9`0uT8eo&wi%e6)|Fp)7l`M7-bGW{j}5)$R+;Zg zdt$@71D0K7WUsemamkhLhg)>4&aQHY- zHuWbWQsuu5Iit>U1O>ca;}vJ{jwS?{ejM&0M~wg;K~sP*ognJoNTxV=0JidCx}H%v zgD{ng5HMx(^77*NLDF~PqJFu!T3ca9TJ~Pl%@_KarF=`hSPIb?D32$>|8OAT7GypB zeHJ;2;ks3jfYW+Mnll`e!JER{7LpLPcYbQn74A6QiveP8f)thLXh2|KHxwa00>=$G zSO^*(c1Q~LXD`idj~nBf2t*lN(q-_P zESpNY1`*OUZ~fPA-{yy%mwO7@1rcwi$`lD>0MF=ov}fOV_k;N>o+wNLqu>WxBZr;MHuC$qz;l4JX4;*KvH~AGJv}AdTmVoO&&#vt&W%rah@jS=2W$Lru;;joUFJVrC-`E2 zXUCx}jwdW}HU0{-MtWL;tJ+1O{ZDWbkM3ag%$YNrNJU3zuOqno=g*mfafDX=K{ARv z$vq+3*87d|B&@uRZ)_>feOBuW@sZ9O?`0EcSXkQW=f9%);Vf+q6akO~KXMkwW$pel zAdurzMF#^l2eH7UhE8Ibad)Cr#ZipNF51w2Cyy{q51{ni+-K7y#Jo;TEn?c2qXhp6 z0URBh50j>Wob6^kA3|3F5b$>6n|+xE!UTsvCk^OE>w3!%0N(M@mXu+LTr)jxt#O>F zV=p+c8>AHVA1`>5}=t>r3W-k<&im-Z+@Xb2fO*rZh+OHFW z^VPF7M<5zlhnKHiGyX-=#g2%yREy(oIO#MAirVj!E80*W3Koz}Mz|ixiI}nRary%u zI90GoakNUYx9xUh5BSDyG{Lq^1BlSm^%$=DQyq5^yU1FkBX-uy*SS#pdkdN1i=dxB zA14exCw((qR<;hLCnew~17kr6a5ktKlJ;2*cFRI?Fc4=tv%~LF+_qW=Fi~6!5nW!2La~S#b$JVPZ+kV&KxM9Fx@2JEX%au zHqZaV+?znv*#2$9R|D-xHiZTn=uWs*R7#qqL@LUZMv(>@D3T`4#-iMk2vMeFZqTGq zBuWt~m840EMor%1w{t(w^M31F&-&JSzxVyV)_<+rpWWX3x~}v54ae^|j?@45P~Ao& zqvw~kb4!}u0F6rZZhuGQVNe-PLfIHM;V3&85$)oMe@agltzmz4>x)<0_oUf02J(V; zU5`YS99tmksYuW5U5J3W?~P=jmzM>}DzG|9v;EXk3ol6&EK`8n1HX_M+{?neOy!Ugq0VZg}d%iAAkZ+JISR*!bA5OG)9rKwl%S zU}g7>P`j<8@2$N)W$(W!sjsu??zTe#T_KV!2l*t*?mJh2_QCCVe(?l^&zWJLtx~N* z&hgr>YpikOzSt-2`oINQ>iW%_q~p1D^{Sj6m+{dlz<>@iiZw46${GLC{W9}Z_trUK zZ0UK67q26h1^6T+ua*1z@1tgn&{lI%&Z|G>uCZyB(~W!iB-3)grhKB7p_kWv&>i{3 zxfV!E>w+Yjc;3HnGbx%`c8fXpkhefQevd^`%0r>h=L3yK-=c$rUtEG8A6=7~f9v37rq{)1JJ=APmkt(4qgQM(%`vxL^ zDNhQlahpAV{wlCYWp~E)^L%i5OZxlX_Nw+*%Q`KLjRo)sID@Jz}P1bW`NQCsFLJX`$u^pvQ{ zZL4b2l=lwqTFUqFi?^v&w*!{unuHs@zg$aSzitkdZprndMD`X|19Q)o%7V%QZ=PVT z^b6mYXAJ7VK)Jw8;6DkJePzq{6BCntQjKSzg%B7mn$)G~i1S z6MrF9Ic@s%w$_xycecNKZ5RCYSC|eXY4<`7QXNKI^MSQZGfOwrPWotMq}_;=)N>dX zT)L!3B2(*qwc7_3(sVA^kG;4%>zT@%zVW)omKP-QYUXcU{N?M{-HA);qe3Gh$U%Uz z3yJMl=<)KExYJnNV&& z?we!3aO-8=m6(xVM36?Z8F%bmR z>`J57l=Hr;YzN<*#)Q~FD&G)#MY+(Rd7nBo#GF6q3nm67rRmzFS18-=+%Zj3(o`;=k2P_kxtEu67@l^%fPtk=OjV;yWR!D4Z-~xH|L1@xA5dUvPfee{ zc=1WIpnkSMy5~j2xX9=R(Y%{?Ucp)>?&aM8MGX!7O1{jY1h5!ba!+UHhne|)k4vSV%xcr&C?uN&=4hnR7-6l=e+=(sSpqO<|Owt=*U z>-pXgaA6Y^^NZl1(A(i2xFxV#H82T?CAV(zR$ABjp$5zLBF)P}KK#$5?FEH}q7Rs1 zCyciSX1S4vyk-tNbmluwIFGJUxmEr!6*|7mZ#$YECMrF3J*Tt-4}mK%(Ehe1 zVXD-lR3whxZ%wb~yESeO>LG4fl{eYCj+=#4-@a6~j;&t9n9oJ5P8_UEAu*7+TZXQ^ zy?to#g(5KoEUuW{)~)3}o%X@_&A4sQeP?y%4)uJy_ZsxHSRHmHXGtn9T5|fAT;fy- z#3Gfat0zsI=rAJ1)&aQKiw1WyG~vS9@6anC0Ol)w+N1NmK`VHGd3A8fe%Wy2AC}D! zixn5IG!bJ5{a%s?Cky}H8@B5m9c2#&>515JKH*|XdpXL~-2)fiy!2Yj#B2j$ikLV( zzg`F0kXkJGLjKtI6?d+lomOqc?hNS-VPs>TZY}@6M&$g;xWy>y>~^33A${yzz*(tJ zAypmGjl+xfWZQ2}MZ087B_gV@d$h*jOEM3u$jnZC`jNln-0l@{+QI#uHNo70uMl>! z-6H1Mv?naxBRp-|QzIT@S$TOA0IcZ*Sr;mzFk+2Mo+2(TE?o6Dt!6Vn`SY>e>n7?B zizXl8?m7)6zkkC-+p@Zm+PZ7EZ%6CcO?bT6I+nJglylq`v$!nw*QO@Vf*>hHNCEsi zTx~0=@^ovB}X<32xd+_8i2>7@WB@Ws|U zpwhHvHlMG+&Mb60&Qg24SZ^hT6Q3$Ph>BRL#2E#9aI@GVSf`}!qNN6FsSW!2yceaU z6zK}s+pPNTiFInOWN%$A${a-NZ9p`B>Ll9J@@zINuwAeCVAFDXWvD@X#<;Kp8K$=u zXnyrcx@-BtY&>fbp6uXovvwLG6Bt>~W*c+1Aa8J)Pp2*x{c?34rDKAxPyrz@M8+@O zlbnlTcH8s0i57@P2lG3}-u!6x`F-!EhVP!|m?g&uJufM#ATE}F(*oOaG`{@20fqEX zb)v;~9k90P*T1@C>zagRtE74D)K{OD=k#Vnoq4u^^mw@w9VT&J`qS8|d{a@i^!{(J z4x0ZwIywIH1IxdsBM=N!C@5^Wff4i-)Zevxt9Knfe0a9-fBF&&EeH*Reb}v=( z=%GUmTgP?HxOC}~7u5gg{?;wncx#*Cx&dBJy&oLcz3#}&8K&!4JR(UUjFz#UUa*8u zJr@y;EbngPKWO&`UQtv+>)aOSzq3{^t?1gJ?n%k}b1=}gy3A;uY^_LXFE^BYyDztU zR)BHA<;dg59lwYoeZD{D{XKSvpWL?NRh}2u+EiuCv$=tNlD)q>VnQ4S{&A9`+N)5ahO$s0 ze486EH*Js1)u@U_krPRI&y~|qB{8zAw{5#j&L&uBE+~2@OrAVf*iX)YHD!X2D(@%n zrsCJz(}qr6T0H6Lmzx`UzD>Jp@Qm;6BK5&GW2LDtM)NbdCVsMU=*d@7#~n5lP}uPEJgJuczx;WPJEy=&QK zE+K@_TyIJfHEOXjvAPTj-c|UgnR!gpHpb=G&yq+-yITI_!yGY(=Z(hGUI#$=2QEuw@HU`)z|dAHRAid z=0wGeoMpQ+EbTp8xrXk}eKl**`j;@X8Fjp~X`4tmP<3$ku5?tVlQEv1o(N~({ex?kh)b@Sxq z(!A`IWN*|}IN7%L#Qi&WPMGQOa<*Aqg5Huc*=C)yw<<^1O?jT#xpQUAJt;oA4F}BM2{H}`b?(R$xCeC2frnn7h zHmN8CP26*O|AFfvx?^2MU8(m=sQyQZporS}6o0Mdex^5rs*Vk%s#GzaQKvM>q<2f<+0vb{&m;0_kX&X+k= zSiV}!c`(EvepJfU>+aUCH+@rPzS=Z@^Y7gakE)i=H~ei>F%ykA7ca0k0pb&Y?^qT- zNgOUTx^l9Gf=Rg1ET{87N>Eu|KJm|*y9R&F_kHzZ-;0Kqi#Olw9IiOua^tjy8+?9@ zPr&}gf2g`{1K3`KkHFzY=&%tdQ8C@Ig@>e%J#;H~YM;J&j*zhCfv~N+H@Idu2VFZ3 zNK$IkLYwSOz{crLzN>@@?IxzC8`rIyI+v|e z27?F7J6pp*JSJ!W*X;z>mL0c+BHhIw2Rqm3Gg53tb(WNczJWoTdE#K~pLUt|ZRzU} ze$Kn&HZgv(T3R;$r71>sX0KxKKraSkui#cHhW%S>?Rb??PPYf{adKQz@7;_iXG%U)=m@n(@Q+1qtD?*b#Pk^R`LLiNYY{F+a-A8O&Jko8Zhw2uwWx8` zUTZleuaq6w9*m?l2z0q!VG1psqu)C*<6SAG^>;npsNo z>>%>L^!h?}mQoloxji51Y;kdO%LBD$X`-$I+;Y$n{BtRYk&+(6Ew1R;RoQjQgYJGDBU|Jc-NUWwggl;N3 zJUe<}ekf+>OXf~Tw)hGHiPvC{GtFWF!C_U$Yx!p(%+Xcoqb`Bj-h>GgKx!cZoZc@s z3K@axYkZ#-6%hi<%@PC+@g2;RNR|kKrQD)LYl&RU!${7?L&uWX2r2@|Ddblq*V&kS z*6j_jsNktQcz{}BLB=l#Y1svcUi^|>@c@7EO<7H^ zYv6OK`{2$8XnYX@pC3XSrsHw9y2EAXP7Bb|1_uX)XUs@J>Fs9A#dH>Kz2k%-Jxn34 z;F>^;2lHi(VrN$4@nyj-n+xECMTI-__;urt7J$vPDUf&J6cu~^JfUC(Tx(Xtl9xX|kxM!ZCPmVP;1@z$0$L+3-r_riY_g+P=8HlK| zva+!tK4VSce(Zzs8TtN^{&M5S)A+aG(Kw752~MM$kYUeODM{Ij2je-7k6s?;A8dDCi*nb?yINYxNQ-7Ki&bb0t~-c{iV|GFVyX%ne_&>23cH+- z5TeQ3WM2iQ`rVx+^<{;DfeV5l9AZH1f=|=Lcn6G$2fyvmzR}fH|8d_5PC%>|^1$l+ z{(S?;FJSN~z*Gw3A~1B1c`%_j@pu+mXIUU~WcmEKM5D<;2Y4mCwHfqr0^`$5@gXYyT84>JAkQ_!`&K(^c(k+jnSni>^u3 z(v*8$h)_KC>lUDIm7(!@08vA283hjl1E3HV{++A_9Yhm2&ao z#ULN+#F1}1z(k&QKXdY=Nu1anq~rDL=k{|DF%iuOLFzs3z{;~VtF8a#0ua{?m9vV& zGXV@oP=I^Auvv}lAmP^qyRqg{mbBJNwJA(~<(@~i>frQ&)Nu>D3-)pP;39(zw$p$| zN)8jl8{(PYzyPKxZFoe)$f!CsNt;vOU3m4ey?6KH27fZN;`$n>nzYobC7Nh25I&%W zCp$R7pbHKUEKh+hiCg%>l;C3HuN>9Pc?q3i2bvWWNeJdBk!*^}Ew%%}OP2Y3UyU>i9@Fy6icDc_HJt1Pn2# z77$B_QVe5Q{D-dQs=lEiT#7b<`2gdvN{rO~e`=5=FkD(Br=GFN^*ckb0>c}FJOgV0 zo7$srgS{;}Dd@sfNy#+8h=j`y|LV^2`}Om(W*=4>VT9q8JH~TDI7<&U2DB*s{c|X% zB4HtZUrA2BOK%YkjUULC&ammC6Ae`JfGULQK)1Y+zUTx^PY_-( z;`88Y$oXwergjcf8Bo2JF2w>xC26jw$Bog<0~j9es?A!D0^q>wE$e|ApuB4x9qQZ& z1yk`?SRmb^^=k!L4L9@2{(i;rWxxk$nPWyzVpPz-zSm@i@<4RK`7T?b5`{FR{JiD? zz}(5GgW>9gCZ&K2{-KD+L1yK3b!jvoseZVNCJVS0Ty|_++{%By$R+GHERc<=Nq0W% z1gLX}pb$Q0IFyrF81vEXmmz{d1oHjybjI&(O7XXED{^!H`}RaGL+=T;0MZMIqYxG{ zGc!?3@{+|p=S$jc+on%GS;#D>a0~~&B&0$#|MDPjb8ICk3#%+IBQOJ~DkrxQTm<$J z;G8LfoI?Y2uC}zct_1^*ye5W+hi{xMfAZuBN-wLiDK`_>x7rv92R!4RH>(w#0nF0s zn?HY@kD8?Y*mIM9jFJN-D4dlLigU6=OMx{ZATnA(P=oW*H+}4Y!6)&9Am2nCvD;fI z9%k#fm$WWe(|CAz{`IcM!d{Ilg##a+d%ZPh8o{uqV%kiEOeEfU3JRupSSV`|Q)mUE z+5lw<#?a1(UdwF}Ai9O_BgN3|w8Trl_0|95GhKM%)7U`6C&#K+jV;C=_q z+l{E|0*|+oGU#DI9ff+Q9oU5hwi}i(bgPzQRI6-3J3-wfDl1t-H;?2aI!m1qNhux^D2MksUA| z&F5mPAqn*sOjKa=eiBOD#3+tKy{C0wU=_SO%b{{r0l5@+%Nmhy?bd`26FIEH7f40l=Z?YOxWul%_^aVW3+Z|13DKLBZ54H0Mrng$EhX7KMvImvbj z5+5!$%@u5+l=pEC6JmgIoSZ8MzS*aW0Ex;A9g0%D%O(n z@^bLh&z@{Pe(2Cz{3BwAGKgmQSX6M=AizRLm5?xR304(BC}3A0jGnX?L6`x;g!L5k z8Y6!U%Em&E`KUT35-NMX8ly34!>X*L;mq{u$snBraxkeBzK2fG&Fvk^H#(ohsPm>~ z(`Y!Ob(~JAfC~Wc!TwPb9UKgyjori5A5XO>TxOx;MK6J7g(4ZmUl167y}U*mvIIz= z$?o*&4BJX%n(ZRtbWR97%yl>iJ;a4Q-3p@LTAjRS2;V4Bt^>TCtkD$&BCz*^nQ+0~ zJvAj7=>|=uH*_3;7jgK66}Bu2fKZ-#9@Nu%`9pzyO525*;W=>Yg8TWR^#_r@*2DUl z$iEA%GR(kwLv#EF-RfMg!zK1meqd=*e!%^|a{00xr<)iK!!_Q(NfA=0<$|u=$Al1O zpLMZmwOA>b2$M|+IIE}>20=B$7{=+`)eks$h$|3M&J=TB?OHvSzXpBNi+BcP*GcLF$U5+x@Qj}MF2|7wgjF!f zSvqvofbRaCSX5XP6{z5Fkr!blxyINS=Ws*{X|I4M2UXrlhEe3Kj81Otx^*WB)8J$2 zf{X_av@|A-Tz1zH!}-1lCdDlLzuPd@C?=2C9X^T!Ob}on?dyC8UFnzInXyQdoTgq+ zA8KzI*mvtX##cr+E%rjbc?dHGtpMgO^n zX8%x%DoVn3K*c*B1t7p;9C`8L_3P8HDVCBd#;GlAZo~-1_2i|EL29ti#+^HFVjGc& z9InF@S?KL{?)99wZLB-7|u9&{iQlHg12fP*( z;z+kKIK05zJO&Vq*YJSncWW+7ErSchie$!5pA+9=e6!15v-_5GOkrpMf|B)7l2q$Q8=ytNkfXY~dR|1p=l?7# zQTTF-2f4X(BRm-Gt^3yci2x?f=YxDA0H*5;mMr;4kvkHoA^;#tu^&Iq2X-bGuml(s z3Qg3K;G=SL`F#UZaIp-s zpvl>ga(%q-ETmiSzX-w4?*deaZ0;JcMdd=wZ-Ocf8wv7kv9Pd^!R0!Y&kl>|?&Xbp z*{@DzW5Bb)$N5z?HO4Hi0-Pg*m4UF00+dW%1q$K1cMIn+a6u@JXpyf0l!AKkV3r3> z^w>cFy9he22b8dILQ#7#0~Hwfzn4Ct z$I=#+lq8RCFEAYeDB0%ZHDFQl^F;%DS;L}zr44K5F0}FRngKudC7NA29jdKVwax-w z27mgmHD?Xf@M8Kpnjq^y;e>mH)(@$Gcgh#r;75-h(O3uVKMv8LeGal)Xh<|{r|G^% zf!22lJrA4f_|W8VK}53TWLaR3tr)?d1803Uj0j+RPwA57g7y#0ZeFsxADD;>KG+*_ z@i|mT5Z$W-y8tT(=ip#7Dx)wf&^6nd1UNYB zH9V!fp#Jwa0?tSA4#&A1G&|_;5r{1_Jfzzv*{h?8z)czZ?)TWUyB6t1Mit<^9w?~5 zUb~6}m3B)t0sNeXd|}KL2&v}W(-LuKpA1wCI&7}*fG)@}on;k+q)YG!k}lLXsJpP5 zunI#%f>2B8bDmw^OW1Uyu7KQ_4$2|e!?)u>)&1=y)0@72eW54-KwutaeWZG%R=sI- zKXI7M-@rgfyhw&NKT8x`ad~+E6)RRunB070TJpQDE=ASLz^O4;8gPJU14*Cvpi%Sg zOp1?it^d<(hT8*@Jnf}PR4|^WVnu^H)KUMo_6Z3IH`*rw6y@jBYV=a)IM#5|0MHR3?lAU% z4l*kaV5^iI?c$^2XRI-xHY&u3+y@;|QLvcNsp8@#>e50U>gPCF*LW$o@Qp=Lbl%+I zLx;*?@`!MQzJXXeti<=ga#)B4OxI~ROq0-*<$(Z$(8PN%Xz`LI$z)0VdvpXn-HB4i z7<-ZUMGoT|>K*Wa%29KV-GLd&N8)+%;06>!@K(F|6 zxCa`QKmb{%3w8sCI-7jBeXMIuxKfW z;<+qdO%&4DSLD|V=?W?E1q$omsY&OzdV#f%rvm?k92}x@u^90H=>!KcM8fD`EIBJ5 z=-XMquZOV0vHhXAV@v6uOx$Jjz1D`R1D3abwAUGSHF#>_oPx!C)v5^%yj+M#xIRvo zRc}g0_o!`k@eby#?d=udP;m$r7_LzG$BLOIB(z*j)*Bucz5V?{)SK0t;--h%om9x< z#I9jcTnS7q(7KZdXB`J$GDD?K1G8cooF$0iv;J6Fb0>gqGRsd5Nd%Px`W>nZP<7$? zL7DPb0@IIp?Bd}OO(iyHSvWqx##Z*R*V_7z=%t-tXGyje=nb)ukBP#5D}w)}jVSY62(% z4wXzolpVmY;j(eae8wtns`i3lLSw2V%L3V1P_PY!_8aIRu0X1eVG#9)=(0k)B?M=x zU4Ux(*jNV!|Iv#;V}cbAVw(d!3TBKiz_f|Ziy`zbIG7v1%!w$3Fy!1j^b%rhPKBLs z;ow!K5w~GnTvS#2df0{`szdK_4Hz(mF2oXygrv_HLF*p?awg76^8h)M1(?y#0wlnf zrP!2EtE>AB+=d;&A21ZU?&#1SPGMMGOI(eiEAwA(f)+F{c^Cy zx0(MM+OxIL~T5{1=eO!9b&~DJI4t-T|i3B-DBU4WbEEBWzfF??(5G zz(Z9%5k;he*jNTP$+ioFOU%v(-}Z(B=iwTPH-*IoC*o#sv$GNEs6-jsv@-m}~`XTtJ6FgXGXS z!&nBvXbe}@3j7Wx12t>LlQC0gUIv%zcB{ci6q9~_?tH_=@JGP_%^4niw0Z4CP$8|| zySMN1Kg$t+sR%&8!pxF)GM2d+t6`$?jB#C_)&QVsc=gGraT1CPXDFcYa4j%Gp#9N$ z2cZJ>QYGpx%#6-0-D3dz@@S$*+&dH*X{M`-t;{R_f{7ErmZ3`PxP<0>BWk+A5<$fX zii1~g-kW8Q;*TR@0@=jSGYh3Uynx`I&zg#$p!f(|19NzGC_iR0=d}Fer5NKZj56AQ z=kOkkw)=~l8OV#1cab3Dz8U)&;@s#+3#`ER=K$0(vH+zqXymn@3PvsmbC#Wy6!LWu zY9CmE1v6u>Lf*!+y>#Wu3OH0raZU}+pF0Cc3yuj5R$Plq!iHkvgeT6Bk410Kim?N2 zmc#FHrVj@Q-qzVUmo@fR{O+L}Zjg6vflQn{jxNUYkR@AuVwe1vznYYOR&fTJHV#}I zrpODT$cDW*BJt0spGGf@_B>dT-++(vn*7W5US(EDN}P9;3zf#`{Ay0lfBeD>4E4}* z2!$GX?cM7FKGVPNl#T=VsM`!RLYC$rU&irpxYARc0!`)E^%sEcMkgB>7a&|4Q?nmw?5<^z`5NEc$-wD^w@{-tV;tHDm8I8x#_lM&f?sX<`od*Vs+z zdcH{ANuFRT-<&^hE*E++9Gi*ahTS@SeSIe^FJAlE|M^bZ+O}v|@J^@Yt)bu4#-|ZD zW_tW=`Pqr!=y87Y4OO1OhY-KVuIw;|6F}A2p+-JAHh=DJ{ujG_YxgY0F-RE0@^f=u z=(n5V8bCR$(TWvZOjnM_Y>XqwYz$C}KR91>s42o3*jhO0kzodG{*aH@^Re#9CLcR) z0j?J9y-X~FGi-Y?WqIDQ7e}gc7K;_CKonv)xi1Fr)cc*X`Q(3rWHM*$meeo9W`{sN z2m_K+ICl!!UXP!_nK!U#7RR;LI{?vV$RCo1%mhG@sS@C~(8Xc23W5T`kYhS=L&-51 z6)hRD;CbEt@lqI8DP<)Jc>umvH}ft(~pGN4PVBRj}V+S z`_Iz#M!cX&2Oy6H0DQnv2>r}QV=9yye{P(yCL#vTM!tqFAA=Uqd&Djdl)+47J5DJY zySKc@M@Iw5N)Xlx5MXT}wbj4{Klhr96Ief8LVHEW1-ZiRgNj_p`-n4~)%4F6;aRiR zD8^iV@ZePGHoOc|EUtP76iI|X(TpcDl0}A;aKC>!m&jinX9mu_X8A#LKG*boCC=mk zc6J%f4*SL2E>eF&pFOr_gZ3W>awM_4RNTAjv`i%_HR<@8O_$g5p7@J*rQQ-fy{RnTsRHb~otgdp5jyi0#vgc< z^W6GV+I9Iy)d_oE?>~P}BXQ69ZjED9K_d;S`1Uwq->#J#A>|HmwF%rz5Z99niofVwi($CYwxrfael!3K0C*%%w0P4-kIYZI<_36%#y50O79IoyKyR8$zQFM79x&LKkGYt9#=%UK5s^Wx zUI#iH2_xaMx%*`V7Nw@d^oPls@YJcF&9|FbTbJ4` z#zjueI?5d+ejDHqM$&*pAgKlb>F-#72DC!l07gfOm+{)SkLCurK6A_u>8#(hx@LUq z7ASfxv^d{7NCrJ04JL6RfP`qyxbgcAfInIzJ?6kb=g(poZfT}|2wh4t-WugE&R>|X ztXz4c562@Kql8Vl#D$9zn9svV)B^-UYJY?5L|7>9Xc~Vg!`O9oVGg1Z3Oo*zDV!%H zV}z>hXMcZxi$As27|~v}!fEQEOwedcN5^_{3X#yfj>n3bgU^@9%eb?6-GXVzCU|J| z#x%FGN-*3NNKa?NgsUq#@53aaPNW$*tpWJDTj=YD8t&|`vJFf{4l_H5 zJ2-p%DK19A6RjzrewWeVUo>z6h*aZyproYa8b+-6KFp3g)g81RiL?b+3xpj13Hw;L4u}B>Nh~5}-`1_3*fD5GB#Ef#)?`JYcyOdKgPrhsAiD z0AeW&iBo9wzuNJdoB8x87l}M<0=wQJM&mOzDxvm&T1DwSQrzsRJ zHPPA;(GyeZD_xv8!DQCP#*79&kh@X<;URJM{)Qt&-Ae_}{_^MW@J`uNPHmteDUbQL$}c6x->*V|1JUHqh>Nl#C2a3tN} zor00BuC4{UzOe-ZcKrM|mu(YD>yu$5$-Oo#B4SxK4K=9Rm=Mi*bou6J%v^zcsDz3G4Rd=(1hlJE+7;-g{NFU_`s8$}o&XD!q}M{ttkW!#R)(`){pFF%Px z`#Gyu0bO#+B8O+gEqQRnSbYB#!U=>-)qhoQ!3pi)Ak9BM_Qh|)`4k?!kFT|7gFt;B zgMrgKJCW5`p*%;&KD$22XL(B_s6-UvFy8>r7F&H4PAGP}=MS74SqS6#4Jc?q8o{Wd z<3aBfVd2Z@9M1Lv;*~z~)c<_7m$&!G1$ksNoLZT4S026~7<;*$pMg@|Z6AQgBjUfm zwYL8F=xX8R)l<4>4(6t?Yk}Fto+G>NS9bspHgj-Dq7N8jI3QS-INsZDeU5kh_|f|8 z$fHMN^YZelciOtUcb2+V9_x0v-ERNk?shRPzl_2XK#6NGGETnpQwU+h{h@=~%orTB zi0_Y|K+n|g9UWIb>qtG3+Tf!TB)ca5G7YfLE?I+QyBD$Z;umi}Od?Qp*i>AA6WAB&0YVL#3lLX9 zOY2ioJDNp+d?s*ui6YS+F(tuq0}z1^+C7vWfi#M${~eK;vE&LRs~#PZULH>7P^3;E zybEcI_@Kb0zzOh#$P%n(kZv&pn(Z477E@>+axI|9lFDq1uJhWW_Ru!;N^8{tGpJk z?tT4x-tPcH#Bj@Psz+)o(i~tcaGJP6V92M{7J-;fJs28xUEt=`i`#+I z9_b|P^BN!a34RS?7Q#RrvnzVh{lMP==>y60@u{Sd#;0oBx^e1*Ls!@g8#AmtcrJix z&^WzXW$(95q#-B><<~NwfzSXvrwZjR>4s2>lr79s7%W(RQc?*MTY|7KZ%qsw%>)=* zdugpY1Wu&!MElr#CM)vTvA05|8W)M$iz)&Pq!g|OSz5zDOVL0KzSN2c3u}GMCs~=( z|LF!QSsK}CT+I*aGF`cH!0_M3-lWz zY0^REQJu$~uoDt6P@cwSlhf_ww#+-YBc#gEdRw2PB4UDApyc?n3%{+vrsTX$|$5p4mubJ30j z*x;PCqbP2X1L3P!9x;T~g&1IvQ@lE|R z;D2rl%PiDWUB9we6DGVNvu+5tbTi$eL>B4cgz?`OaEm>*T4^t_#iSr{((I6h(B&)S z4qSppNq)leI!(0$82+OlnByD670?-b*KfU>=an?Uw0?xMGO#Y9fB^v}&lf0xlQdb@t@7 z?o*~ty#!5HE7<@TG%+jz0Ne8g?6QRr1UESRk*w5tpwp%B_oz~hwLqx5M zjr=|$wj*^+D&8lJCJfQztg=g`+=S63T)SXKh0%yebRC_bLu>&2EnK!}sylgQdMSP6 zuja)55Av6^=OX{XG%a*FQqj zC1Kpv@>4zpL1!aoN?{{P7+#UBXW znFe9SwdHiKE;w72bD}f~wtNgwE=crko3~u(MbhtZ!CB4BUN7<3lfEEuomd5JO06JH)v0-wh7#?GV9EE&o_U6)cNkVePKe@D^#AC##{%! zh_Vr6U(ueCp6+gQC#S1K0^RzAMQP}o~LHiIta-6rP^oB-`6A)+Wj zD?ffzw=?G+uF0G-eR^NWo;hl2@15IifpeH7sM)*FS?Y8aLdy4j(48QHdiS=i$8Q7L zEL?c&IZ8bY_~8|G6geqjFo<}VSX9X=rJjAupI~|b)97{#p3(k-&Uto=SBe0OW#;3P zfr3{VX%gk)Gw1GQ5O9$Wa)jV<1UD9Eq1f7f)W13PZGAJwp6{`?*|DsILYPU6S8RoGMH0*K9_-t;UNgj1+M z-h0f^*3hVNHceOtfh}Anfx)Tml32VkQQSP)xE!QU%Ks^q9RMDU{Uv{bOQ_bAnkIv4 z&IL8lAP7FSx$-0eA$=VfM`-UoS2eoVW_gpd+av{TRGleSN>@5j=YfX_e8cTW{cY{4 zFd8&0Tv$44>hAUVfC@_U*O!=N!{<9)T`OqkV+yx=W13BG++2T!Z3xk@JqbJV*#mB*Ms|nu(%cdwn9FQ1+XEXyxZ*WFSmG&2^A5q`cV0)%TNCv#` zIeP{(L4TOT(b+79%6++cwRnR!K$<8*RZPmmSF+CVcx)ymh};Q3O4k!L+wI0J?VoZDJoJ3UgKi=P!1JC$ITJCieO7WJc)*>6`o&mVzeQ0p7ry)YJEh=z0$uKNx zi?|W4gB&kg53WQI@y1~~VwQVBlS*#Rz*DNAk0)SF;((j7vT_TJ=D{vllPGTRs19cb z*P5|2Rbq!r@`jH9g8g#Gx&o8N2RKVB2WNqXOE3Ypm`kE9bBY!5NILT9LzW*p6QT)K zcrV=q%3bcSui_)$_vI>*!YWn05P1Rz3MHxB_F1tXUx36W zh$hMI-+3}?`a>$=taA%B;(-1$u8RMN>QCXioz?_%A5;BQ2F-f*=Nh{8 zU~V2TuPegSU!sXQsT?d`0bRBcQG`T3?onQsU2k5;1!Q#F+dC>uf-{=7}2G>+} zxCz2hZ&9zoj^TkHf>EI&LPANXtj>JwgB`Ce=65#hB{BP_mBTmu%(1WLJw7yO?-?iJ7&Tc@6njs4|rLGc>Jmlnd~(>ygzMz4CdYB^`AWcu{1kar#K9Dl!@AO-jDD0 zOnS()Lysl$ju%_wC=L_UnN+!F-_=4N<%X8ou;ks=J8|l&q&!2-SFoV{Gj@OaxuY4{ z+&nz9z8{97UZ60q3e_kq&R#p@^6jpKrP|FK8`H#WK9%1^orLy0uAvU}1tM%_-<3!C z@8a^^e1~63yQ|*vy6Uc{R{iUMrsK zXrS+-g2E1~IAS zj$}dqMhqcv+mxhw?HymGLoZO#{b+wdrv2CF_vSRUH#hI_xxe{rsiVs>&8G-e0;b(U z7|@h4iyUv6Ls;7r*&6v0vH->2T1EG5<8RH1Id`sOTAlFkSPTH@M6Jdtym~b@5Rx}+ z_un26k8`#P>!up$>-QXx`xz9(6uMtV%LtRvR-s<|uLsr}9^a>wGy?kMpuRPRvSQ!E zMQ6>b?aYItnbPohqOwS6{=74XtM+A($nlw-2A$%7XfT`UKeNX{@q5XA2dARpIB0eR ziXVWb;wz^l)CRHTFMUyvp$jK11W`NSb;b6t$s4S!zP+`+?N(cLFyoGB4*$oUOA?o= zQe?HXbaDF7)zuXcp`p|qo<6Cq@w&hF7avvMI-op1v$)dSQZW1g{gEfYR+imo3ynfm z|CbDmB_4Mbw`yEq4n|LG-348SkAHe%=Od4X;F6N}FIQB3%RY1-G4WGZ|5BbQEbu@y z_U7u&Il5#qFq*;IE|ooQB4@m6&Ch(O8kOh-jv1aZZ}Fa4y~@C|!rMc}59G&ggpBI7 z#!8h66OYR&LON1CcP2W6C}esn<_zdjNma(_0{4WF#?`^$K2+=!{CPt>6_GK?Kd$i>P3$R-21xv z*x&cy)RM`Xb?#o->GmXGA{TWPkH+39-!lgy?!exSflW%@Q_ze5Y&Q*jWc@o1guBFR zNAT2<3zsTyy_)3x*!x9q(fKor`&Jl~9NBx+Vf!~%E-_xc#I0Tz#-At8* zZGn^Z%AeQV6dcr>cAff#g)`se?j6QDnIM)QWSatege@Hr{KkDW#pjTU0#ALva}~1V?3_` zRpcyEc&s%V0Z(AHbiS+TB(mRit1^j{}oxx>z3sWkHqOnrF_;J@iw_$v6OqOY=Cw z0a=sC%h&|TC)r4_{&EHup|!`s)W~Sj{hOtZjq^^&oLTyP=F(543E~D(Gnh}0T^{(B zitF8*bYNd?F0T8SgyzS&$BTexQzcz?*Ff@k){rL;w{(J60U}ey+!ydGDfgK16zrqK z{ex;|80k+^SjKk8XQ9rr5YG30!QMCYGT(TaJ)jWzIxVH9rUe~wU~jUgq&5?r~<4NP&j}dGGlmG)R~_|T{k!?((ty(0aZCh zc~HB#tKYEsp51L?-tPdd+%r$AR5mVab-%4KzEJug-;D%G`Ys4n5j%%c}KMQ6uQ_Yy1n!Aa;lJc6mu( zZ|@lwTcERK>1}1f3KfwvNF1#plSLRYSKW9aBPX|#df#g);h6S%{AzK@-HKiURxBMs zlFg2saD*gmb>2j!?knoee}6bj{R8 zW{-QsInSDxu*L@>Ej%1Dr6-1w z)f>%P*F(fzPOIrFvPuE>2R9;v1@uQ2n z)4siX=Od{01duiWnB!uVxys}Dgenfi5k(l2kz|EnJOC2q(_!0S-$k`776n!d2%jvj zAuIKIp&kW$9q1hd|K`DL<^i-+wB#lT3NFdX#kE1-SJCy8%so(ku5m9RQxRy6$s@@y zN7P2m<0U?IvSb-f2{IvmF=>r}9->?S z*t10jLw5`tjTN%Hf?Kn!;Q|3LnXvDs=H^GWs^`)t-lKDf;8;{)ux13uM^caJTEO<~B zqXA3BL!+GnkXeb1N$Ti!Ns<&^? z1jGn%U#zMIF`tkRl;|m`O48DgoA$6X$zlUV82t?23SbbVu&0z2gw!_$r~bvWo_! zn1X?|UONoj{xE5vmSx|fqeN(wQ}OUM3`NjuiD?I9o6d>>qb_-TOy=7ewtgf)rCGp! z-8oYE4edA*fitRgXK9*2h*G_8GuO;r*`Rs?y@Lq^1~hVJj7dLrpD*W*Cvqd^R<(PF zz`eRj-Z^GxAn$QbnS2;GqG{1&O&zJw%TT_j=f39|AWkLBrY|)aS!-EmcH_f253_EdM5MzopnZB!5pmMHYmvUKChpKzePs6h3hlcE*8HHCcoF&Bwx{Q0rjE zyqxh~68Hrjqhg-h$#;;==%Xhm&)ds^2VU3^w zSE$`_l+Utr8vEZY=t}{iAMTe~zP;D0-RfXCZ|~A3?f#CMQ#9WgYfF^XrDAu$lMRkY zdVisG;Kz)bPVHId|72eN8Ny7#wV&*y+Kdi%J{BsHm<1D*=#5$~2SBNf>NIHKQc1;x z0a8X&A4F>$7x%zX4Zeo{8XvVqn|N~IYU7LnmfvYpsnC=b0F8hWdtlnKR>Wf&kwF7T zn**;WB{}2=KBBvhTRW$ld%%dskt4|%ldj48JY=5eqcTW(Ee~ zRBAOb(LJ?Wq7kM+Bl8)_MT6##=^s&K$!#P3(e%Eao)(lE>jCD_p&bbG12sS1*VNnu zH=q?GXOnY2pT2o^L*_~>Gz=aqFn7tI5%70{3BVq+rU@XhM*p9|haVFlhUAoK%|lMW zgj|t{A-Uhbzin?Zy*>$jDrqBtloq?C4_Pgf#%)IcERR=lB_>t+$6N?A@nuO#%CQZa zGbbn4grFzjs}Qli-o^I;Rv;F5st6g^FlliCx@5JI73#4McZF!4Fpj^1lRBL-qC<^- z*{*&nv9;hM1XekSc{N!FA*f1&HVzNpl#HB-*$~9Y9|}spH^z_zB~4IL>)Xj|?iyj( z12ATzqZ~2SCrJlDZK&bh%r~O0C*0A^tqz2$TF0S;^?XPQ;QUu&XsPKq;W*g%$V}zA zGVFpFw*UY^n5nDc6S?>0|JD`>&FHa);q9`S92CS@T4uVX@=RbsW*bCqAc7SOc zfXtAl1w@GS4_b4E%pt1BJ7Exf;G19IeTAHeI^Y5w!XcBjrvR8oTLtAAzWxA1M2JL0+W;tmjWv%k$LTCJSKOCkZb^O%;+B2jf=Xz!mLpwz}=QM_6`Ls+4^`*paR1bApH zQB@s!!o#oBQGyy7!=&^e06a<4zI~^liS05-+@8RV5xh6gVP7ZjKH$+ z3_eCcBl#Tl!~Y#c>Aztw{h#=!Acct+SWMCVhYx8`7yeI2TiYduD}%JE4eb^O4lEl7 z=Yl8hD3$ge=JfV{lR-JfCH?=4Pxn93`u=D7TdojmiyV{zAhs`EINiuQmWTd4kf46# zvgM1hOEOvL&S7-rtNs967(afPozp+%8@`<~_J;@_>9On1@2|9!nRU9-XfwSq=ygl1 zSIx<@XRBqM6`DBjrsd%7=H_;`Y4CUPC2&*mCOftny*Z|nvHaw*#hh29?Ra#aD{o>b z!gk%N7Z<@l#*5mUtX>DH*0EQ;S@MEIYs>yr`mKLNr+6QS#aKUbcXT%U>({U6|M7~v zJN7o-Exvt2_EOp3r@i2#_sD)Xd2!ujZk!nI_V99QEL@rx#^+pWl~P?4UqO4of@`Pm za?{_Xl^@V-{~yG?c|4Wv{x*!LMXDt#QJJR{B14%aQf5WUoS`B`R3tM|B2kD8k?N)t z6-r3ToKU0z8A6mfLx%S_mwwOtJkOu+Kd;Z;`@Xkjt#w`3Iemv?=oeW+{xBh9QdE-s za+qt#vff*DBPHjrw$86ukZkbgqCW%c4dz(Lm3m&Yy8D&V5!TJp=U&3|XY)$LiAl|j$=MMj0toNB`b5N_~F_?)-t`C0EX192%E z9LCQe(TQQR-i@2KDQ z)nVKer%`yzSrZeNSPr#~WYGLgCiZ$8wCjl*^+v4Oxs~cG$*CVbzMxZ`T1@)@v1fZ{ zPLN@dG5a~LHuch`z_2mv+FGNtycO<+`c?CM({z*6VpbYgjrYG zqb`cqGmb1yY~T}@m!Eth?pNCrFnr^bf=1)d0eZKD4C+q+q3Qgi24bI>8Q;j*NG9OQ z535!ku5bCas~OyO%Hb)-^%!Wc;2h4gr~l)?gV$lioXl= z3HFL>1H3yb$e-x!*4KQfVH0S$ZwVs}acE=^T z@cG$Kw)QIh{i0lT!)a1SpCLf-(bbDwl%<7La=&wXHk&_lsM&l&=*sqAlgmO^eB0gl zWO5)W$t73w`B>rE?UOR??pF*&Gfo{v1xV-kjaYH9-q{j&)zP7FvX1=wd>N0|E?f)M0mL^m`67<5(OW`KGD4vFf?;ne7`!bywKSth2XX~cfxD{WkDAD8RqZ8$iC-wY*v7!TQ7cKkmpz+`7$TJNR z$Aj_4s`uvynEZIFc+Zn}hEdYSlz(aCz3VJSB?_p?l0gf6{rl``(~hlwVbAkkjeXzW z=&qmJwD@WKpX1)0&0p@WE)d+?o30|BNgD*UjO9AdU#6#b<;Pi4>W73sOH}QCNIsvs zMoVbxOwl)O)jVpl-@6Xs$BClk_nL_U*AA%+>zq@gqG z%qSCW8s$RvG`P5tbGXWpm;{3)>CYcN#0vELXE2VE@$|nZCw#vMUt6xdz>^}UF|}mz zQ_6#b$2JZfQIXU5gb+{Y*j>Tpg=F2U=??GvZveRc*`|fj7%j>|s5I^Kx4m&M9=K3> zQHwnEwL0Dxv&psa3UB?59NBL{)yE@vxT2eOVr?7Pb!#YyjZ7RCoxhc|9pCPdgSK{s zZ~tq7VDT#2sbSZ)?AwsR^6y)_X7cXop@E+SAMFd|7=?Py00#Wh zn(pLnR`RE67E-r{{CQ&4VAw(a@9aS_9WCI2_ZgQ6E=wS9QnMJ|TP>w?JoDe*yX`qH zr&BGooV*sMSSYNsqnrFIotwx-(BsIzSWprcao-~sARrfJ96o81M2a!2OHA<99p(@a+VNj2Rfe=E80%4P+El4;`)YV@_ z%<8Aq-$m9HpBPIxk;C z7pAPWMVUZi^aGV*q^-RyJ#=wkc>em!vVJ?)b%n^e^SeLj*iVE3Q5?ub+NK>76O-hz zIIDDskJ}TM*4%<~4?v%udCfDQO0Xs1C&#R!-DPJBut!h5Cw>;3|AvS8KPsG~eJr$3 zp!y-oNJsf~V4I@eI80o1`;a%a0F+U^-mvVJ?HA(h<+@RxAdWw38a9hk_2DV*|e z(4eER7r(=wtVY`oc&Tf=5=0LOx{SqRw}wa+OO3XK)yC1HHgtEFR=3E+G*ljczl%I} zd$~krM%rC#7DH!&y^O=l@5wOCQJ7E|Llmb$oLgPaA&v~4z-pd9-&scE7SlzC zH@xa67Qg_OM2Th4hMsp6ss#{Hp_Xq4!XjZ4OhyS$dFkTvVa4>1sp;VlTW<(OLy_cj z8klgw^t5MMmIGZts^ir!znYh;`TgZbaDlTaDcfcjUW9>D+; zGvx%`ukUDki~q43XdXZ|EHI4M%+m8ZDYpRO{qI`hRdm-~A#6~h-{9r7!*=mK{YGd~ zQrG~$(jjuu51;?s{O=i=)Ij+Q!^z7Je+qlj3K{>H<9h(=v5R9<`TT>`>(Dku?9idW*Lg?^I=gD!{H8>!z@Qbc>(5_w3!IxA+_-^Z;Z} z(ic(JypIKE>Nm2^j}OQPPTJGz=#;YDK7%Jl%qVS+@X{vhDYtX;HZFT~bQ*{YH^g%O z4cC+pcDq5-^}E1sA*@oO#|=U!BZI%j9_+q8J2Nl8&4gwSu|**oDXg?{9Ik@I*b7X5 z;sMgXjJ8qpIOTtVa+W@ITP+l+fX8lHS3JzLJ``g}4xA2UB>O}+n5_#^$iy#=xXBWU zB77BgYJA{HRJlQ-&P4U6Y;mF`L)Zty7#JplQuxfD{E`Rgh~deRqif{9)KoPrOh&eg zC}$Hh4zG0^|>dBdU%dqA8_Bh?y9OFS@gY2`tvyMS*& zWfUYr;lzZ{6S}S=M_Cp(0!ux;74q{_)YnpEC+_ENp9;mZ4_Mp;vWPI23HV89nS&Aa z@8TXqGaO)wOT5GP!I&S1?KR+|AySJgL^%{0f!OIEDA=?j(G`ci!U?ju6y(5 zAS(U;@4_PY%b`)8NQf^_pF$Z0qep(%uo+b-3?O5`hnrwXf{ zFbcC&#!NkcaFXG>M>d+pi;vC#F9&-tuhau#u>@DIe$d{#|tBu ztv|$-%sOBPWT2;w?pLTrB{ZWDN*bD2`oYi>qR^=oKm$MwOi*5_E~Lj~q17eGTwHwW zlx14W*z^$%STD@9c#hS{kNq27(cmz7XkZbF$q)GwF)X9S30up!D7YJ_riqa>M!gr< z0W44QWcy9c&BY)mM-Agdg^l3oJ>RS``!^^};r+M6G(jCA+?crHaiQWzwAl>FqjOIn zU_mp2F)$EWywOas)Qf?rr!cTRz=Vdp8-#oK{=LSM9u&3~V0Y3IA{Mt0zgv6)OqKhoss4-iU+^LEcxD^lA+$6H(4B7pr2XGC zx%|e%NK+BbT1mKi6KPf`7A{WiQ+&0Kd9ZrXqlPh?S-6GJCS+#jzwt}C3yC1iC|;@z zo(x&IXpb)rd`I4}l6*Noq|k_SJetN%7q-wQN(vZXkyL7;yr*ysu@E5b&WOMzYL7ixU*6W_HHTch}9V?h{*gv@;hcN|*umqKIp}u9%D{@?VkMO* zWZ=$XOQA6`Tw0|UZ>D_JYbp3Fzds+9S%4#ToXmYJ-^GRWI0u^1s5&#!C$)gYP39xf z?53whk|!_%!E`>F=uV^Om4%*R8EwOX72LTl_}vV>ocsv@%=N1B6MVFJ{T6-iEDRa1 zfBmUC*_OV;?K5jlvWQe6-Q$o3^^UT0N}I^2;;@mTJx@68wPj>v^Z{Gij2McU_9Us_ zupuIHp)eFs9P`Z4KWT=+qCjGu7B6k~_8}}PNMn*Pf~5LCrVe#+*PM~E<&8a+ zpfw;cvTtTR0szunM)-y{Lqaj9mT!qQ+(Ki)#{2iU%poX}>@%v9pu6RI6eBK&=JgH} zA>Gz`T__;qF%jAm8Z{a#V*mmpREyESbHVhQVy9hQf3FIor=#w}*-eO9ffSjN_8h{Y zDuG|Lq}Tr8CaAZNkkAierbIm+z;0+fYoyph_=5QS0Q!D+b^~qTPU#SB6qMWoDd`Yr zoI`)L?Bcw2%lG3fuf zeE``P0tLG9M*EyEpBF&H4$=wxA*GquTC0;l4@pEcl90)KetBMgfQ2?sWln;~Fet&L zMHIoH1UK=B=VE=Y31lb;T@q>oI3yp7_p?^j*6s(v9_TFM$h3Iz33-Uph-HW-=O9dC zO0b~$f5t;spUe$(t_UL)@b;v8>#rgrMN|2xjg1=Q3>L3D-WMV-B&TBLXC+#+tHAGK zQ`8#iM8CA6CSlPQ6(c++U}JktOp4Xgr%pB06jalpy7 zX5FBjeH@SymJp52TetR@UzbV6g2(nj^0gu>$pAXG(2_tp|9E&1X;W--Pqr7|+hK|+ zfVQ`h>ikHQlZVKMbEb%d5g%YyQy*B{6NDwpcZ_&;M$dzT>tO zQA0o3pN||7u%)wwBQqWEPr_rp>HH8^I{bHzco}j~80~(@!eZw*xMqllk32bb6Uz7` zamMKkSp*YN4t@@sP~s>P=8c)80vLHSBDC6<4^cY=Uw#)sw4r+}p+CO;1zN!b5rnWj zT*`m_TiSP$dnPt-Y)c1PatPSj?#~2rKtj&j3F#zQfpD+WOGj8poLLSAa?n(4Hp0d$4R_~Ba+pIi}rX9Ek+r(mS*wUhw~*| z?@mCG4@Jj&kSjuvi40`99hV>ov=F4i24!Mx%@aVI>hp&o*|t{FN|$Oon%F)o{F`TU z8}=pug^t6ThDbo(j$euo$KB(q!O-b!;3(xdQY}iydmMVcK13J?6%cCq^cLTlrj(y# z26Ptl8mxmvG7Pblhf9}0-+yskrcy(R;|Ars05Au)dFJ}Gu^gA%>c${kAcq+Q%cT6p zAmvM^wjVW#Mu@s&W{yHtzYlx?I8Wm|`26fdBD$CGbOINj+2Im|{^}r2i^BvZ8DZMk zg=rJwv8Si3dT>>ff$CNWMp094W8Z}8BogCXWGfW=O9{Hdh*UNM&x7{=m6~s^0b=J> z+34wbxyWr1)B$XN0;e|MlWA_k<=?e>qLE>QWrAxJ&ndbM z6x8bS-B=)>3s2ugcRL#JP-nS$$fUPC)BR4KdHf50Ky$jeAJf8 z5;Fe5#GtBojP0!uv{+kaCI+r!gG3&sRe1NREhpw4n%RxX%I6ETuu1z*nj2rbzJ17f z@8OvX<|Z}UcRaFA(@DM_()Y6e1vxwNS~2-?RE%Q`sO1jixIx*K_f0fi>2feM=vyR`<{UbO%GbzRq&nvD8 z34+y@UOm?t*@S_cGj?(kQP%|$iymU8@Jxg^Q+z|27`W@HggynQ(u#CUS>EFK!7BH9 zt2q`NKt(Bs7!gyb7!2Ce0He_Ay-n&50?2=E6|O_NtGdrevC z!4e;*KQ)$lhwhs_5liz($gT>xR&~2$YJCWUi*f|#lvGXj0pq3%d(CGHHWXfwHoxoS zv~!=`@ACtzVn%xuUq@zyZ6Mkw#HNE^_uo#-R?bRU8bm-7#JCXiBvZ$L4dUG}jYrr- zaF4zvDTZo%5qHGW(@KNiMiq%IoXSrUGOJ2fHekNfBKr8Z#E#K*)t&F6HPR-vlr^&b z)M9_MDjsQ+2tS*Q*YAX6ef1`#61y=J*a}9^x^cQ0G`i z3Bty$JXR~iGP0#Z*33G#cE0?A${bQyBMKsp;^u zEh{l`H$RkMS@AE!f>~(oyX~#g&esi}S^R!3o7*c_ zGx#nxaDI}7ziIg?Bi0?Ghhmi$)bDILXZWo4`6|6*k#CI${(EkIBSVSoy4~D8IJ&nU zda?&0C3ao#s)%ejGd~0AOrV4dVni{i2X{+DPz2Wkd0ArwUBYA%866!>db_eH}po$^1a#9w=rX-6^%K@uZZ+KZF780o?=$Pe{v3L=blZ+F8#AN1nGt&j+kH zeMqo2l-0~>%CJK3il}eEF3O0vRO@)yh;uP?qg^lNZ_#1GzGm6#_z|fZYs9UF^6;%U z7249myEd{!-1@Qk^649~{DoO3%`{p)rL#vK&xcNV}=~*b=NZzu%uf z#(PgYzS!WkmF!9#<&S)VE*1!%s=~Lx-2>~q5veqQ^9j7S%i%6d1PQ>ZfPHBtESakv zAO=j5Spq^PVFN`p__0_%OQPVqjSVwLtm$WP39Z&mG$ z#&BD`q)-2acMUyIA0P9{r<9n;;`aCd{`tkB=H{+V>o#+I`1C5y^UOersFe35rQrl9 za+8ihAf@GtEJq_kBShv}oJOePn-j$1kJ|5JKiy#=JK&`Hcm0d2{Eku@Q#x;4W+UD{ zx4LSZTYbY^=7^#?*V>EN1Kl~cTs!|~GdY>B!6&Q}kKx|c_L{2j;7xtHF)#kC#PLvU zk<1M^AzSrs%f8U;W66_e1fS*#h^c%*#Rp`*y_hj*NXobS#PHgc!t{%T+301#$)nOS zkF8qB9W5@*7%VLhaL5_xL!=x-0(k~Gj@Lhot4iKJ_U84E8(Uv$yz3OdelTC_-EFcl z*GMI-;T(ty^nKUFnp=1CK}P1^SnoGo?%i@#_IkXrHT@wtsmwh|?8P)UdaJem<{_Wj zpC7Y&&d4w+S`ejdAhp>vS$6=3`$AKw5C&OC%9(RxdaX^tf#CHi2u(!~8la;QIyedBz6|H2yc zrs_<4`9rfhZ`WdBjmi3Uugcz9ei4cxeao$<7}SFsE=v~Q1G1m08Ih2b^Z~P&csO8g zV8_!a)I`Y((%0|dPS-v5I7SI;N}S`p=8%?NvX9xHBrmqdwqdsM_HIr!$xXawZ`Q>g z%scd~_E5q`F_!7KYsN>5?$vl7DR2~f{2RylT=DAa8#PI#D^E0uNvWjfZCuc#PF+O~ zPYU6h@l!r3%5&pQ5kBRQuzpEx0fD5EmDQ#I3(~28Uad2DDqI^k3X$!1CUfGe&XqGS zd1I8#pG8!9cVyW>Qo7udqnOO6MMr- zl}U+^njT~D7Dyt3xSULwObqg$CpBli^9OgVkT$nu^NJUC4$MC0;J)@*wdLuHtM}$a z%NFhlZOudgC^s_IBz?lI@__G4@LZi zV!|iw3Lx=6(4pQIH$w6?gwPWb$}(LCoH z*~fa={ECFNb6xWO>)B$SS^oS*ccr!9KD)?_tASl}ZiNXKg|?Z6pI)%Izpq5Zsp_M& zVpGAR*Y@Y;3^+!k*cnwoJ0!+xsJ4-U9aNqf*$gJ-d`n2V2^2-BQdjnStge33b`oZMseWKjwZG zCgJ*%gKSycA2@S+pNcxn=f~!D@U`atw2wE}<|ch ziZ9tet4aQ{<^1pS?QfTfygS}m-aNVKg`3^wS*NJoek+~`lVP#=m|u0R_Tph6rHT`% z!`~;fY#$})#-r4elKAOdN&bj8kqI&eGyfy-=MS)WH468Dnu&2~B+>-V?$_?@46}%! z>PKJo)9BJ}yXse<_)}hB+m5W9&q<^y(;@JmfOQuB7fZKvQXh3ow4HE zPq6oD8)fN6+DkN3WJZ54-0%y2x_0U$LNs)?*JHK9hv3bUd_Enbe$wXEyAg36YQeCo z(kP^$--SwU6PEBA3L}M)qwHMA{{-F^oH7DN!ik5Q$64?&_S=2C<-S((`oF*}+nQxY zAiLpax9Gu)*pOA?2yu%USb9d89H7vcGw!&|nR|~c5=OyunSK%2NCguI7)u~m5 zhlj$*fC^_m0dgZ|gTWuJ0<}iSaR2J%ixKvv?E80mYjg&; zvBuQ?c0v5#{ohpJYG>1$8|ET;0tfio3j*8Hj;StnKAv!mtK{Jaq4sFR3A%qYC5lD2 zJzMb7`}2#J;=_wW4PXs%`J1*+F8n=nqP-Y>%kaQgsf5%9wSAHiK}_9H!tnU<|8VF& zfe6K3KGEP2!ESg~yoy^hzOp)5S@OqS2`+0uT0E&0{%xqy z`ZPC_1C@z28&uN`J37yNlip$6^U(YOt+3F!-0iwUHnaCd*`j_wHb#|h5K_#}$PEpg zB8p71+qS7wr)EpKaQnZ$+yzvJnD&N;*S;^LB4J0%#V&)&QC2YfddH62kC!Z%@wM-0 z%^T=)*Q~KOxUn_;(7S66B!`I%+?^}Mym5YVx>s9vrvGvhVOoSi? zq&Gs0DJ-^1H)igsJML4n+G9Qq`TY+6Vd8c?}pW>~kCg9WZ$ z`;bo<%8WEQw=KY0d4eloH(;TD4`L-NV5` zJwy)KDq# zhO&A{aHfHaMk=FHRJo#kuf;e%R7NhOH`Onwj^66$kBXAllnyhR|L)49RoGvC5jDTn z8l1pRd3uhR2j4He@xNEf1AHRI9~Nk!eJudmuK!iyV7#M0g>NeF$ustM}vg3f%n5v{isj0k1I$XW723x`l!}mFPU*-?owVDc@ z-K9-o+*WtKD2O`D7qK!FG{3*F|B?8g0y>DR#DI)(R1Dwl$5NUmxAKNrV)=C)@p{#I?z_eiC&yHG|IN` z*rCIlQi|>1vblU@B_^gru1GYq-P`W_mR#Q^E%tB7sft`aG zTB6+S#((!c%IGvdE?eB&ofX`2R7S^gxFi3|g#H8Q$tlWL6E$6+fXIeZhPLLlKwrHL zUs9`zf8{#W$5j0gX4ib0ci8v8(og;O6q<3$qi1trIHjqn=_&NH5sQ+96YYntVEuqK z;-=twMxoyYj2lrkWM+{04>~iz(t;I)P*ut9rvVY{ADSF1hE>bL)>FTOwO&}oRz>q4 z_7)1@-OMDSEn76gBe=U_$+?^tzjxx0_8ly#2c-z&87S2e{qpA57E5EQGLS5huw081 zJ=xP-n>GnkY774FHbJnv6#zaY48g=FcQ@3o_qY3(mv(W}dHebVk(iIWg~K+t9pT>Y zJ2i1nY%|P*EAHx}H>XSLLHJ7a?VrDRVLs%>j3b+CU%B=i%Fpn|d5j4yiKsSoL zetja`y8Mj*t_p_mwyYCvK$;{H!df;qcfHiz7AG6L<`r?uLPYJnPuZ` z-eqXypv@tHP-?_Btu&)ZyZze94*v~>E2OvRYp9oVw@s<8Ns5TPFNvT7g*M!5xI6=p^@aVd8Vr}nx0dpp`N5iA;?2%#zfVkohFKsZW#Y-SCj zVZVOZwJ?OYY_QcS(tvI1v9ajkXd#v z)zQ$|*WYq`w^u&;#LUFzG+W7ySX%qdW3JFNP@ubV<>dE(UQP@Uu$EwF<@S1x8JuCz z_4ZM1x5JW{=pFG>G_%ohIf|wk;RJ)y@b$;l_;^u_9pS_p0TE)*`@iBK!F}%Z0lc@9 zzD)ad^X%kWQvoTe)U1ckkMH$0g~b4SNh{TNu zMKc8KIx-P)oVra98sohn)u9%h85yV%R^Q9r*ZAp`nZ4fD7@=)(YE;vhxm#S{xRt+r z24&3xzzdUwWi2kIfEuB@6lr&=E0+NXSoN)aXv zno97C>-;(K;+rdqzqD^!&OUnO_+W=Pi}$j&!-tRNQd!FE21^${mWMwua?3V(>^nU6 z$wdwc9juAXL81N##fq-qHxB|1i9p@!bTCn$9|xjyHREmKf=J4u==!hWC~uKY0J9J3 z)#|{%E{7GM1*f&&-M6bsBo2Fr)Ve-9`L>q3^^XkGyWJH>IH3^di9&0A_g zJM96qGV-DFI@!mdZx;M@RBZ&db~lP+d=$;CxM!j+i?am7=DxG5i_JnfMh6%O0FXQR zv6HNmKnd*e5=pV`UiyCqy`*)szr3oYOuv;a`tG+Ut?%H_`%j+~?hGuG)CB7kP~ud; zFed)|Ic{$+n3)rfD!k?SUr&p6lnugnj@%iA!6*maMv}DQ5&^AaeH}L4k_6KO5FU@g zyJtB%9~K`T6bc&*HBUvWR^Kq%n&-SW+UB#~27K46xbz?AV9~Yd*)l#SM@J&ohR7NR zY-DS{8UTF84h}*XHkPG9q(#1FGLf6_3?l+_IgBmn+QySj2A074Z(A{_5Z_Y-6$KM6MjALU&H4#vujmqBJ zf4F`I+5A50v27b{!D(b8ByPrlco`|FR7^os3J{l6j2{KfOCmiO%iBG8du#r#w%_>< zHQCXv3HpNZYhNcW#09qXopUsXy8w>Iwd?(o>KsvbJqCs&?gCqHc=(C8-(2${k+5c+ z$#eczB1-GG;2Wr>%Yr-uumXZqfcsbemyIzwV{=9t$wDkFd=mTKD^9f?O%putc*{PX z!ela;rgY|zQ~vDsalpWucQm8e~knGaQt&g1L?<#*BH zB)v8lIf$MJ3YUZtQxU{$s1GT8$6ZMW2i{aD)MJ0ijXIq`j6jI4lu(g&+qL}jmLE0@ zq2JH_Y$7P7qTk~`U?>ohHzde70f54Dy`>!3W;m9;P85g`77>{kZ!#FOaV`(Bks>Z1 zzrMXN1BV+2e#HG2C(cml?~sf_Uru8EYxSw2#Nc`TTi)|oJM+iljPe8o`HQHV+BpvJ z{6|2Qeo637CGr;I>wtANnjGAk*Q(T|SkT!8J-wJtdDs^D6iNFlI#sB z+hjH9Q$iKzRd3DDEg4Nw*5WNl%F5|@H7_rQN{yTKEt&7Jp5KifJ?cTCSB#GQ*HcSGI5{+QA5@vZ+PyI6sK-#= zH4VnV%RjgkQd7^0Vl=S6e@e@-?!wtMgC1lKF*}lo6TclL-`MQ*Hj5O-7&=X*I6uHp z<}~55Z<~0INaT7#LKX8{A=?#vDqT65*5q_=&9@|LwDqff;Bq&{+u#EjxH{` zST#u&7PA*%={ly1x@U3wxAcZNN$OIG_{pgs_jX!ERj^MaDBjYi!LVPg@=b+Hh1Q2i zZ*+Wp&TphANw8s$Av7S5s8x->6GA?H2eoL7>eupIeGE z!Aq~38ak`6!DwVp)IoWydQ?%_8Hd>bQd9lgTJJGV=5Rvkh*}3}}Flzwz%4@}M+ez_x+uK|oJU?N*Z~%w~ zqq&_xy{5ajxENB{-UPPsttc9a+0)7uj3i2jl< zrS4;*O;6NJ(q8A2CtHx+rq9R%AY5bj_>{EU zt8**)GIcBEACBzG*(~L~H!{gfx>imjd{^%oRiXCM09+=N&w;#^cdd{6=4u9A2Fz#3 znLrJ$SZrYBLJiokLx&FG48A=&1u-Q64>Eg( zc8CU-GL5Y8I5yakm7943<&k~7ZjR?(x1*hP`DT|TCi@59K7)U;8tJq{jDu@K(#(qV znZJK0piM$NyHHVrt74I@;~s2qhyr#|OGCa^O!;tea^g7M^`V$VkQluo6#dGc+Vx)^!XzE|@0k8>cVKZUfc{?`-|t-(&0$PTo%S>eoat@b14 zQ>aK0<1#FNus{M+93h5%4I{IgTFOL1L;z_YKvm|R(mWtUM9CEx!X#acz7-l`S9s=w zNFPnap1LQ38y6w$Ex)^N1a6gP*kZqzUkJoRfa$?zS=j?T4M?i>rzh$DH2sl z>BKtt)WFQoyx-2qHSHWMi4>+2SG;#`&W%QPQcwcv?GBTxxY|(|#a!JWw<` z-6#=Q=V$^`R7BUrG8*-F{plgjO`Do=29p#Gvr}x_w&)JYCYY9{qV|pH`3hiUfaT!N zG;R+bTqyxHu#`(5wH-p} zMu=Y6aYWcSG&I8u)f~0|!!)sHTZY!ByIC85p3Lr;yOWza;=}HB5iA@KLG|I!S&4Gf zBOBt~L?EZAmS7bkLnE#bC=1-j6y5a9Cz=$o0Qp+YcxpY-3qdBgyJwvVLVj3WiqgI@ zvb55z(5YP_Tu-1g(DvGiW*6WFZUm}KzZ;Cvh~8%W7=X>>Ao<-ualq^9KNJEmgz%-+ z@2_9AG-&6!;Z#zgdwQrfdYm5!HGR@mrgTUHzW_Th)Ymn?J&uB7CN3>W6Dwf{c4>5* zw(eUkAmjFNdEK+g=5;r$(o2t~AcL}1PR8edJN0@+Qv7|TiqJF!qnHKN@Oeb<+@x5b zzq>mFYdjrLLTHPd<6vN1*x@_*qMg_;VcKM(|I-JGLB#Vq2PDXC-UD0pc>(|5f-;>@ ztkpiMTcy2$u|~gau2V~m{3*3pBf~Bp+aS0FwYE5RX+3!!@OGYeUJ~bET?!tUOwT|I zX;+{4B1fsvs%+Qf; zZB>@C0+OlwzasOsW;cB1&aWAbs_z>r`T1YgK~;r10^`ogk_CDUaLJ$GADYZ70*m$p z3R8H@j|BQfJ^_~n*x6ocDTfZElb#<-$0-lV>A~%+n4Nliqz`vjo)Ert&XF@W)2#A< z*JZ(7*lfhM%e31(MDh%3K~m8A4v(E^Jm+AZ|A#FT9_jcRa-x7tco^9)Qd>Li#xV%A z>(P7)r9yfLp3vy*SEOuCTesl}D$Rf2ROpm*%~qOStH`hP<^w$U8Og4 z(G*2$!c_=Nu?1)fz)2&dXpuasDm??AHU1YWdD=(ijNo-*=YT*Z;_|9^esXZgwpg%x zCLTiK-;Z7daj*@mT+O0ec`aVj`T0dDULAx-Kxv5K96I*R1N;Jgz`Yqa38PJLsOa2d zGBaVVHL{TMQZXv>r^;Z-LPA4v+QxujH3}bJFyo$^;)!)OCSM+RO??{Ss<@I@;5u7l z=j3)=M6R+P^xaXMN+j~dYmczXEqzQW&t#$=V$)bop=#JYc{ej_8)v=t zX&S-pQ5U(UEBV> zOQW*S#%3RSPrJZfb4vEof)kO7S0r>h=YSmf0NJS*sV{B+f-VOS06vQbQ_czKxk#}81UqWg?4w*rG=1ERO!DWmFRmtFI%lX>;DJvNTZ@I+`URKj zTZ}^Y^YUc+GD{gaG+4+7(09GO*z>$`7nQHtL3Lnk%z%$|CFE6~&;9u_0SQ272p6if zMn8cJ8IgUXH3^|yDRn>vUbj9cv1&CaEPPVaMO??))L8kdThfC#$~p*rl<xIHlvXifAdnEc0CDC( zx7UAG<5OFkME;k$H{b{@fP5Tbkok#BspsDv<>HuSBQIYW-Ki}a9M6F;otEwqsu98? zd=w%~qJ=r0&NH_Md*!NoN1UFEs`2@#0x1JCpCl#B^r@t{&py7V-5GDVHLtSERsEE0 zy7llgU9w`(9#4b9fsS9~>E3t!go@$&CohGmcDo+jjzxocf;~}$DBJ$YLiov)_pSs0 zb5nHrG&?RwM0`LK;y+;AU_e4F$ztX=VE>u9>o+4p#5#?k5gofR3k`Uzm>vCeAy>($ z)t($2m+*Qk$*w8tb5EbO%B?ED=_>(E?<{{)Q855%`;SoUC#RYDmK(SxfYnJ)l4O8b zb%T>fTuz*j?Rj_6fBkf4g^=INb(mA}fh}Dh_6)2Iq|mcFMeVU_pKq-8Fq+K)&H-FA z>qZj;OEsxDeIVYmGP7| z*CO0+pL#1l?l)h*U}S3A+-=>0VFMb83>(DLryRN?S2)mJ`goCf`SPyr01e96sVIy0 z=g!KiGZu!oy;iv}J2iCP$lv%-j0% zx(KWq{t^ml{weXE!B>y<;K_T0CKfR5mO8yM`NsM2+Xg8Dl9Kfz18=BG;L<)s6Mz)> z2^Ys_boUS<5E`p!?n}vBB9PShk^~8ssW@|OiWnJ158-#4t~=km%o{i{D{aX^F9;hV zsCXTK2mz>L12K96sM$`$q|9oT%unQqcxp!V-}d)&Q&k0(s$|3+Re8P;s_(+>v%o|V zxmiNW7rqeOIxz7Q1P5;<))R<)U`^i5u4)C(K9QBfa3#iKn?3quZgH`>9BBXbUeh|L zUiA@j9cFHxedw?d${&HNAPBfQUU9b2f*`?>=-dU|Xza)kF%DG}$}gnTSno{xw8}2d zhQ9m17}@MMT$mVrF5)w@A)BY%z7n{8qV!8Rzoaajp*l|*I)DjbmZFSmF}6+)dHa0D zFK!UwW?eGEkEOqIoE@}HQC-%wds_kubs$|CV9v~315y!B4+Y=sh3S-q2G!Zus^C}m z3oKx2FwC!6zy8=~?j{*BrFCn(reinsa#Q%j;HvFtkA?-R$pq^`7%?!?6q(xrR>1_% z!U)d{9GcD|zVYiw@hr3e5W2UV&e#4&gF4w4rJmYqF$aa7hh%@vMwJVZ5Q|OudTPVf zw!*?OfSw@kejkX11BkP+)JWN9B+4(F)L@Wjo~u`FLK)`b>sQS5vz4`q5yq4e-?DHz zM=4*&{I5rruw2&RV~rV`sOuAIUR9O^TIl*G*lqIe_a}f@+5uJRwY|fZM@23MUORvi0jtdKa+u_Ys zm7!W()6?EA+)>fT9|CGm}Sf@5Dh1!zGvz>X=zC10E)qA8m6WnCT&(UPU70dp$aOTYr=)$}H=w&e9W2FGM+7HppzLOLxTSOnc-v^DPf z>dKJzhtK&bk=Ok%JDc!$9zq~bgI+g+4K<(uI;pRERmw3?cwnRa7SitdU5FA0wkJ} zeBqBdVKh^0q-oEPv5foX>HX<vLHl)WUe{WVYbAW74YW{Q;6uv+s1-8-%+~m!^ERzor zcY4na?&@85NQ&@%)i+`WvAo>3&~u)x;D%2#o0QLBFL{g$)+%*=@$%RYB| z8d!`S!PL}C%9@yVuB)%_4d&}B_8|w^M@S8bB-RN7$^vbkK>EzER{2=lVCvAtl#RB> z)3+vGe>Al`_h4b{1zT(ctpf`ssx#JGST5HaY8pqDu{((?iD|Qi=dDSO7jX9IJg*Yk zrIBv!%3e03&PYri3C)^FU=VvRbh3^iDN z&x%K`oa}S9{(BShFcijAYOy5Q%ryh~D){0>q98y{7ecn*t*J?6kzxi*Foa4uB~ZuBY% z=5V(gYhvfqTwm(BlL*bofk-H*_!3VrWr7)e7_t}N@GwmV+fFR6@T>A2W7#|zR0f_c zNaM+=ob2^uJ@8*_l;LgQy|M7wFt|v_=!Cr299VYR-Ce=9RQqZ|!hP7CSddNE{Oocc zR@#S31w4LuA+zv+Mkyz-gJzI`4|zGi@8XQxz&tcMX;zhatQZaP{Jiu z1z^EMVf_Vt)u~sj_8S{(@Rq&^wB5CyHWl``St#)Js&T7Zq@Q*DVjH=N6{lly3~)1q zquxIMCm&?SeY_Me-Stc%R4G0!W>qadCFkUcAYfsWq)IEGpfK_4q~Bq`F?qjqR4f_P zEA7aL9C>`}D0W=OYS8IO-4l-mWU!5f-s+xgWN*@q3! z9)QPJIOx>#EJfyx^DP-C3XexecL^DY+qFO)4yeI_sTEwbIeLshu zGVu}wJS|p@`hhkjrMAh%O^c?i-h{nK_RT){tsI%-rK+L0IDrJ$9Gq|t)n?=h*Z@mq z+D@ze{;m=@MfWa1&PzB{cjQnn$YQW^(C4E1FUX}p$>PF9mh}NgN8tc}4Ne={H>A}J zG$2fMpGs}4^)RA~u?Jv^AaTa0>;0?DOtakLSRH;%4Fl_ z=H_VGLT0m}k3@3pnDKJ;+4Y&18HVAKz;WUGa_jf)bKlxwb$(UNhUJyCWh_~WyvO1X z8^%AU{^;p(EA!_i<^~sjIa@cil+1eqGQ&<`I3(pFx&#mP>=nP0nOk80fR zf821=)HDkbL50qez)I**jK3VZU=XD=8U`VHW=8sO+M&(c>8ZH=^PipSMb4cr54tDf zJD)l_IW2p0+n3I-+U_x+H2ttaY{JTX?HWl@cqOf|hioV3S}+hzvAikk%1+~9Q8_VB z3A>9-HOOh3YHBj3@$yQMJD}QI{K?}QQr<(g+qIr90I9bYf$@_}0@A!zrsCEIq@Et! zMgB5a>t+E{$oT?;hvLdV&ZXxbYBgL+*@lswneA20A(aWVtofRL1$toXv`HTW*TWHe&c&CaKXwyecQFx4a}3EK*&^dtWMcIL|o$Q$!>OtI3|p1Mmx z|HrFJu6Yl5BErMJ+c6EVgO`{G*#AT~8ZI67+Qw6iw0J)-e$4pthIIzUlqH<$L3Ap* zun~bT2t5HB9m=(54zOv2Rul=L)gEy(KQ_|Hskk3Lwj$H(B^tUG8FVVwU=cmgpw08~ zZ1LDeU){2du*gWq?)5l6KV9+s9qZ&HY9HC+mS$wtQXpoPg>_QoHCC{P-Xexbgy0E& zI1;6tiHbTJde3akRYhsX!|?pctFCvo4p}cx=#p*nXsE5NO`VZi+F^|powgp)D%Ub6W6TR8tpcbb3kE_8de>bi(@}?@yFXFwu@9=!FfU2#1fT7KM%FoIGQj zXHR9lL(bppx20FS>CQGCA6%2G^>*3EZ98Xv>dLIHo?Avgr2&rvRQNU#9|J;Wf!^Ho z?TE=YWa9{+c6lnwwpl(H`F-3x`}?Jv=702eB;^@5i;m@}u9t7{Aia3$1IzsDGcq%O zqR?~O^?AQAk#|E`FgUQJls1Dz<90>u>w39Nw(Y#(&S8_?bqD{8Px^Q%A#ZPUpS{T@ zc5KZZ2Bf1#QfzdrG62E52mLg|Q)^Upar+$`H{~N;Z76RQ;8Gfvyi|Q~_IKs?6)cza zWZ&==XiHSfdW3>ZKa_^{5jffJzrVgX@!2^C-64NN+7-~X4Q%|F9$vgtZ~UXqvIV{9 zrgbkB-3t!cy7kll%@ujKaod4fsNc;yK0avA8H%bpuzPo)FHVHO3Ce6yY=PM!%w~*`C-0l7at>a z50N*5d7SmP=qHaKM;mG|(w13#l7`%S;a;`GhacvR*{TYMT=vA|9b(ftJvTb*$h8si z4`n}^?!*zA^j63qWMy484BSAgXxWU`eD7JgL-K6j-fs(8!{s~7v{wok`M+ET=Z+1a{qz$9uV6JUiO1uxqskTS`Ot=8YK=KJ+ctxI;r*g0|dMj)t9d=8*` zi0oKhN}czU9EtxCVrYJSeSu45L~%vR)UC44OzVw1B9e;xZq|Iq8E>-jJjgQZ=;)gM zCtiZl2yxvev|#`YU&SAMbcJe6su8t^R%%NeEf|^Pa-DryW@oZSx%ZYk=XE1~^K9h% zbx(ZZBhe2)N_WN*sRvN4Ql9DvdX82&FbG=kh=?$RI#>v`RPg%ihJ9SeW`eYC&ht8Z zt3F%(y;j;hduX;Pxi2eD$rU<3y3vq-xd2}>Q=q*_eFO?G z?3Z+C2Nm5|?CWs8E6-dTjt;Cf7hva5J|AM|Zt7gr>wiBIB}v|caQHZg+BkUT5fsA}&a@Nnp{T?l~3q%?s0J_^*9 z4a0sZ@)Sn`hV(S)c&So5DZKkNwX}Ykq|C(rOP3ix*3}0w(>@)KiOxq@MaAlWONwzi zQ}@zgK+^)TR`4jLLjEV#a(b84Kpqd&<3#CsKe_6zD&oQg~p!-o&Q;61jpb+K-gs1sR5MSBWePH6Rhe|15&u8r<)J^ z7g>R}K_FuUCW@9F<*fmXZ8?z8Zm;-%n0phjn)mnbcQw#L$UHZYge?)u)FeYhl39af zNNAu4sgTM%WGFMG4BO0>C<)uVja!CNZ9+n!lv2*?UfKWO^IX@t{@1zAbIy6rx_-ZF z@7-GKyT0GgaDVRmeZTMb{pxd&#UYsxq)Xhd2>O`$hxq=?Q5WEtUcqTQkOHC_Zbsa#(D$*?^Xdae-YQj1n}eOFlZ zsgNA+5Pi$va%7->gmF;#eU#=4$MKa!>+slz53|){r(W)5dqd?QYW~i=qlSPCXt1`} z(9+b>{wm=xN|-m;wc8 zS_;dygy)>K-sqzdu7QY8Ih=Ey*7LuU(Uxq8rXsYJp58d*(O?;g>JphOG{$awPmAb_ z>^ox&FX4V*hHE1H<6Zq1Z*?^~?gY6RHbk2q*UhM?5O*!?dvR&0@Ow$V(Ai`h$RqGv zt(pqUWncqaXgQJp@Bm=ieaJ}4ymo?a((iK3-cI4<(0g@g%4zWi0*SO~lUyti9IJY} z<&tE~oIHgcehFfGbZUjvA_O?w?>aa#+J}cP`t$mAL15LD^`Id>K}<=?5+PX9kgf0^?m>IE)378z`(OGl#$qy4)+og z*HZ+CaV$&c3;iiSjuh#Wl<~<=DB`k5=6_@Y5`uq;CSvCdd zE=p0-Nf{I@U5)rtSN9luNAe4e8a0B7SnGQmd&=HQ@*P9_99%aOdYI5emuYb)@0z!1 zBg$7I#DLru4?1++Sk!3*NLg{TkFy ziVCTzOaLzhCA&5K^h^*vhmJMEtjri3>FOp;h=tex?c28vx9J7Gu8x|)3Pg$wuD~y( zwgg%ukFt?m1!IjUh_!{HXfWq#AlT?ElKu2G`S9iR z9G6wsCvd2!W?)f`jEpuzd}d8C9t);TohrJ2Qh!N%2Hsm%6+@a);56|G6*`>|35F{| zBNG#08oc@}V=!sFBJAa}jXjWF#DgA%zsJ0^+jhIjnd=wOz9Hzrp`-kFR_UiKmpiPi zv`DGiqEU%7SCL%`%y`#JVLgh25IZG;IdFr8IPvPUW|sd;*2Pc)gTtOJTeJ|kK&i+` zfAyK1nIm#J&nZMRal3dBO!bqmQvWs0vAi*YD8xYQLZ_+Dc2Cm8k5&pY$xOPn*&B>7*^m)IeCd)mgt&nvyo8*mx$-|MBU2R+ z)>^+=XE_6&>7BqA#a4`Bab^0L?|7h4PQYf#5ybHz(#lNPqc&Hh2{z&;d;6NRLRG$6 z+BV2C0hH~EDTf5b78fe~`0>qi70MRm)SzHUTN+xa1-`k{f|^0+i{FxxEJPvE=KP3E zpL5cU+hs3P5_X)@-(6OrRqvuZ9A__`Hq)#=wpjVul&L|EQp}JEA17G9txpU@|-3w+|er+*) zk7a-3dsi^U)n6YCed|7fkMv`Mt}FWv!p^F-YumS0*mNcSqz%^-Y4!#-&cD`tTyXo& zoyV{r+MF@#O~0i5!uU6kg|T#UP*54qfWZUYl+l2v&1iTN20|4OA}}1RL|V6o1-b62 z{4fJ1a+5RX>({NTvfW|U0pGt&+eHzR(2OurPZ@zBJ2Hp4{>udrt{a|nPnrvp9Kit( zxaBsC(?K`52)VJhca;W~Lo6C7(jL#dkR_dqAaxvLcS*x^xX6&fW)ITPHzs3vq}BNk zFn}dX8xa{KELg52GyvV`T3)|~? zcH$Q3k__Q3@3UeUe9pb-dapm!7*VXX`FZ69(s=y+{8JH9JpDcUt{49$oGyqX9M~(_ zaGJZY6rx8)WQAam7?)59}o_EOiF#pmwqA%j7p1M!&tY};8=kb6q?bTGe`rtWvxLC_C$-i zVS5|WDIFM5a9MgqCI^5265szDD@`!Mh{rQ(s!X`j78wIslyvEmGnE4i`+XoG;gnor z12uk-EoUOrB`fg8jT;>nT|`K^fZT}kQ0WcMDLKSl99ZSnrp$_1$bADMMS!Jly?WFK zjR3C**GMa#ekW$1cn7dGpw+P?lipmH0tU;{^Y>O{)}OB0bNW{;TGykv>@ZAL;aHAj%ecHLB!nuG1EnXl*^se@+$bicMHF4stGYjoSG?E@~<4hXk z87e|0=fkGj3KNiOh2O_^-lxDRGibY0sn9>un@RvQQJ|@f#bbcTh!z%%_5l_O9Zg~j z1K>eLnID#xRUtNvtPXAk|Dy%?2#ad1`hEY<_~&_Y;1P&fhiTmcM0JRgH5Opn)QfIo zqhxWFX$s*^_-HgE8$(Mgyl=k6BM;JkDr;|C4+KG7dIMq29RK={DMR zCHFq~fGl%z^iqrp{fiEw;TjZO$kXndLX{|`ArE%^l3Czcc z1zPm^TC<;1&9I9ayP zhJ%}=R7mn)exhy8R?;8sk{n*4i1{|mfddDgF%3bx&IFj1)z_)hs2~eHkLr0dxQxqz3yQK5rZ^?J z#a*x_45Gp^jB0RAxzo#@BtC^7MENFu#N0r$?TD>2ma;CCP3WxkuXa5Pdl*lO0w439 zU70)Gfds-Jw&OUZZ)>oNT~}w9~0J@O%0h9uYfZ#TtnYWm7G;5s_tMW zrLK@L&zSCR+#(;t0WxTm~nB`W>HK(_u}t|5BEdKKo01}$N8PRbQz8-FJ^;^ zDQU8}ENwA<0Z|x=gH)3oNl9_-dg;e0aKr$#vkxJX2|&*j%XT#y45lTLDMT3s)n%9M zHY@&_dmd)%UU*EhGQb!9UAt+cRe-2MQ%VmGqyNf0qbBG*XAXz$F8oQO3t1zq)e!fv z`*&&Y-i=}-Sdpk0X(=XqGu~kx=VDd8(RkZrNDKpYlF?iea4B>Z*WjF3$~bn$v;wXquXi1&2^cdY!I1nlBse8Lu#{fxl;YMtdmQoe!vT z?FqS*(Q?I-JMm}~J2OIqH>jn5oG;@f?lWN+c8t01fx0YwJ9Tx_1HXnR2KQ>o@0ZM_ zpYZmc!zcocBxo3oZ-#z9?xc=)SaV`I0ut_mdcU@qOMDZ&UN%N;1NC~dlxmY}XClG8 zYW@13cIz8(I?+c{)H5+exS&rsBt`qsBJ5VK6tNK)iLZc6C-go+j9V*09#NtzN|0o! z6go-?@ChasjnXsg)oU#KTsjp9j7ngSKgI#{<+fj#G>U+XF77Z#3pjze)fKJOi_T*a z>8ZL=zi2nv4@Jl~|HRcHqdBi8l1mfJh(m(1f`jZ*c`d&7vKLLo;i>P~^mg6Kl}@~g?dSo~jGx7WJ468%5!KF}9ec5= z1VVvbff?Q8(Ht`a!o+$CyGP2OL|L`zajxn^Mxy7uHx2|w?^%_PB{|cyX#%8kAcql; z8=oc;q^BnCoAf8KFZ{iKUR8v`a-DRkKm|Z^X=&96YZ^mXv3t}?w~OzI$}Dxf#1aH6 zV#z4}qQLk~{BQ%x5-5QdxzlUS+#hq&Oluw?eL~PMw^lWJh*@!M3Pe9A>q~!PzHv|v z1K!r}R}=;jIPh$1RB-1uOx(b6Lr@t=9S86t%_m&gvN!2^y)GcFO;9?HuLEkIGaVqqIiS{$3yNzN^-b^1ARE68d(iQlS4f3xWVg1S(!-A zY1F7qf@x?eZ6M>pfi@u1s5bd9HeBmQSA*itQI5;MNB6lvrz3|`#uJvCJwWJtNmY}z_7!TT>TJ*QM*_8I8#Yv7`7KSO zzTcIi^qrRzNhl?p6jo}ESwc=G|k6;}+v=)bIgsl%Qn3VkxUq+cen8RCQcg_cb-`&;;H|TdW z?esJ8ayM;)vJ$qC`sl#CTTPa!fXa?U3qQ-&|1`!%yxjSBsM5$th-S;^(W4D{T(1XhS44g-(TurM+DF{R zkUz^Wr)6YjIw;lB=_A9+z-;4yipZ<>6;$_*(T_omLUF7`T0c+@R>4`>n z08B>!CHIs|xh%?BS{uM#hAU-XSs~3_L>Q0O4E)$T1iR7^`#t@^N26u%EB+e3V~_F4YxiXrE?khb4&gsdG-RJcb_-v=0oiF8*Y(i)wh;5^sI9B0 zA5jlWM#E>Y$9z)oyWp(1MTh{|dpRzZ-h_WJyER4bzN`)pytHKbzME7bQFPx2>;hH} zeQ?-}J#fs@ZAMN>hH{1Pm>FtX#MIJSeZ78CJ?Wla07H=$*l+&6>qStl)T$1LGJIG~ z(v>Ajas8csRVF0uvojwVN!1;G4O1*-psE-wVLqOLt!k%E!>!2FxT^{Ezw{MwKF&Le zb14Kn#P=BDiAjD21$9085JWI2)%Si{r)^O;+o<*F^y{I5ilVQB98kxPneT+3lbhC< zyn-OrsxiIYYGzOp9)q=x+9#k3QA}65M04m0Ji?(%wGAtS)x;_cUmk`pWv80EOLvgz z#;>5EmLg(fsS(ObJTOR+BT8#q?ycbU?5VwD1tU$Zg-u< z<8l3g0|(Zw|Mp0egeOHsrsnbB)Z~@QJSp1X(AQjQ|90+qv5%S0}!&aFC@Q|)L^*AC6DUK8@#68c8x~^ zbA73f`Zu)SxpU`{g1UgBwX`f>1@uuV)~JpF(2+*!D|E`NIaz7I_E@i~NK2fb>cBw4 zsO9#eJ~$nZLaC@~*s9g-J_e2a`s`Ajx(>bJ!b|sh>b+L2T=@WzN6ZazgRpdzd!B;j zD6s~LqHQQlOQEUK4+Dc~(p(zWy;rXUktF_ERY^>@@$U3!kLGlRu9=(T$pk&X=dK=s zW(ljeYn1BQ?QI1xEr~7)@xiSrUA2{PkZv-qgQo&EgDF-omF0hXOUY}kbQYM>EFU0w z!Gd$rd%X*y=s1C}zd$JrTLRXe#X%rvP~Qvn)QsNSAx%d?MFL+Nr6}cQSik5@3&^jPd200_+PjC&Yg?NFHM2`{A?fJxDkbeS^dz$V&a5u7+wo9_~j2INu=Yn zBp=9$V4`S>MgDBNpY096lK)!x%?4@R^*{`XlemLYvp`5 z@&jP)Gb`vPq|iiV-wo^m#|e!Xq7XW$KAd|j{x&j-v?OD`Ngx zF-;mZ8em}*h=xT;X=x*g&2k(W^zg}>x?WP*t{*LU5=1Qs-K7X;lnP%OiKi|Jvm1u= z5+wO-SMAoE43R-r23v55;5iWQh+lx$#r#p3(tf9+6npIL=eI#zY-m}u4{&ogx*Xt? z^PE`P3pq=XwIDWRA#Nb*{09rJ)&Nq<86wevKo6?5_pG0%Z6h@bU(*w!=rF^;78C$oHZ~Z!Ho6PM* zG2D?q{@7Z5cf*DZxlgR6R4ru(IT(@L$tT)ovpK2G-23=Sve|Cbr(dL7@aKUlXDGoI zJp%Vd4$DfGhxy8B1R}~%kSE!q+GipS)>==N6n_6;8M(C4l;|00{@2b0K6W)qW!1r&EmJw_c6j-B*S%!veOY}Q{V@lMCd zUS2~kRetpS6$U`zT(xeUk+KoYUegjn5pueJ6D0pa=CO)aR(lSWW>Bg7{?gBiOBC=p zG*{iRNAkgiY!Bsc*fkPwPWa#)O@JbBs0??mpA7i*<9-cJK8Kz@<{tH6LX%Z8QbKmF zSMNQJ_Cx9*4p6F2GDzY>qO9<*y7g#DPu29=>Ie+|(S4vX%S@ND%|VZrDIE49+9dsA z1if3fOr0;QEQ%luDW_N7p%`1`VW*Au47lGfW^9d^^%(_YkPXACQ}1yI3|LGTwuF?B zL99Ks{vnVv>67LMIa3Kh7(5yh;GMf{N~+cS1ecvaj^GykXSbNpv{S3nAr z>bUIM)vI1?C`}J_$qP%~SzXzX0Pz9SE64@-q;rG^;BH5tY_Ij-ak|Rkc^)G&GLd#t z`Z|R3RClh?cL>YhZ(YIs^0>HA&Z<}Ks|RIkMexLm$~ zY?i=MWY$Hj4rh~ROfR;2N#1?{Z1Jhizsav`s7A^g@Lg*KrvUw|#-P8zK@I~=qNeC* z&+VRwMoXdAS!xhRh&Q5x#P?jHXAF;c^+FWU57S{8{4TOxBreIFm;YT70nVdVvE31^ zX=*fVD94rhThdM-TroPb6%M;LXHCP!2pe97m$A*9Ds$^NG^?P=iC4$EY#UY^N(!;(Nwy(otf^3rXOvY753kdamWkZaD=>@h1 zd3c@hTI6JQSuWYGuW(2vmGK@tM|0_h$?eq@WtU=1ymdvmuh~LXqhD(S?Sb6C3ZRZQ z0+c4vsOixVMy?8THmV!9{7pA}AEdyRDXKrkxy{_}KX70m3RU{5*1%~Unt`;?CUlvp z6OSZ_dradx%}h2E+bg3dLz`9cduGay1A@OVEbO4H{!=aA@UcfkyEff0#)OvS%!iT4 z;tRXvfA~|~b306%5wxk`;uWTv5Jkq$r$yqgU*AS7O?bY{wALUk)o0S;Jp%5#a44y+ zXdG@p>il3z%71;K8A&}tjz;130rTg3!)N;UO6O?6C(&lOJ*Tt^`EuBf!j-LQ18OR( zpFbV8n{+mCNXJ~TtKs^{ZCjovmt$;TuvFh+KUfT+r~h8_`ltPGs5<#~yqz#L)mLf@ zg#^(^#+%tB57)kWP>ODL>*Hl2Fx8@zUl%tH-xtAV61y>Zl%1WO7t2f2qwRmLWM$<} zz`~WbnYdEFX~nMzIOe!+$AcYp;OMEo`A|I1Wh=4Y)lasHbTT5N_!Qi=K*8t^MqmKrvDT-43+LDeCu`!^OC2+o^sVU|RwicZp6^b&q zU*sd5PON*8$!EuP=4lD<4L2+3VOv6$<>trvv{Y3s78krg95FigMFUSgoo$pR`WGA~ z?W%_)r!SkG0{Ji!BwOe^#c6L_OF_>YB$`|CtT~<_`U=s9lq9nNP$H@X{1)DQg{*?G zP#AKGLIzY6gYjrZh=ut&@%c_;q*CtR?s^H}YZzUc8R4``=qZDljd6C4gZd!YdDGP^ zCjW?M$w$^})ArZW4a8nZrUS^MGk^~qh46p0Bu#~@@oV55`eQNZjeLkGpF|7vo|gN{ z?jt5LjV?viW2?EYswzaJ1d&#t0BfvNTb1n%_RUP%$oeU2G`~fSuvy4`h?7fspKykg z^R`ZE+@{TN)9CoKXSdv)%E!oJspWX$Bnkc`Ii9E}r3g}@et)NfkiS&Q463nK22*q1 z!EyIvdUAlB#S`r4-0Dyy)t}U7SFhQyg=-)vphqGqeR!G>YHH=R#8sRHkMh@&yff3U z=%?==I>p2O3)0W?f%+tt$5HJgFP1&d$Dhwj4P#b2VAYT zx*|;N>fY{(9Cglp(%MhR_zKsF9DnV+8KA1p%%isHO8|t`)Xh`3ID*ODWVp74*`TVb zs>XNb+i#3T_GrzP5F5M94!L-zjyu805rSjbrfix!eNj zs*S6RS?f9bsVS#{lW~S*6mW?fV;waK&U}DpBz+@|vX}@8fF8cR{Tjiq(_pZ7E~_ch z6rLknD4H8$t4BeHlfp<;Ry+6U^Ss0DeYiu!#jV-KIxN?7+&+S(NR&DX(;tzw#tj?( z<2-GotLxp#-Fe7{$!pZZTAcv=AtenYLP<3Myk)m3;ge=(5PJqdnCQgfWvJ5tE1$EL6Um5lhQ>)2YWW{s z0HE|jf1HHBauACqBenD)nN(&(ycBYj@O?B=>%t+q&qEHMhW)JBd~{7k@JJfH;AWjc zZAr3x1Q{CNUaa9<4y(wi3z{W_3IwF-G&lr06&Gr{`dZ$l3)mO&5E*c}@8+|icmcRS zf-4EXb06W$wzX0SeuT!{<5A&i+^>2yT|m45&qq{B-Vdp*0#?w8*bl9vcULw!e^555<=Nnw+~ciW$RTi3$Rng!puZS})-m_<4oaF!J= zStuTLkLz@-Ct2zPMJhX?xM&0546qo;d;-+0h={0qmre99REx$;oKJ+)AT>pT?C!ig z%Bn_^GjW&|Y{5_}<2b)r-^j z2{Jcey!nC~;c}94mu*XebrejFq!yRJ5zP!5E7GP(Y(Te4IaVWnYm6z{qQrr~(kOUg zyyV5s;w5&2*Z*^G$u8o>%H}0w%?pz%|M=hi*8jT?{=YPm>IMU4gcPYA!&rR^zg=(l zgi80)dR^gN9}zV__s|`&u`|71tZUtSKQb$8hN`QE({Dvi&g8l+x?j!Bv$eG?uRJ&C zNmqLt8=KKOIj`Q4VCVJUJhof7tWSkPPtacCipkgE82 zwxmJh#_>cBJ4%3f4OU-Uvin6qU|{856HYX`R;HXXK^KIym(T8Ixbi*=03KJj`uQP0 z|MT-%qXPnp@6KyS-W0hO#4hHoo^$5KNATd0o}O{?1Jw)%jOFd=rx&{J(yUptD(7O< znl+m*UApvQw!5!y;oVt}*M9XpQQ-0H)U=kC!AVzc10@b8Wt?#GOC!vN?;oB%t)pqQ z$o=yQ^*{RQ~fr`t?Gm&|T;QZ&XtAxJn{W&Y)e7 z_*|=zkr(V7sfXmG?Kjto_*v+)ps^VLg&)o{jQjAlsazk(V#nM1dhp{pSP|ad;xVyQ z1Ux%-?3h|sgxvW~iwC)RP@{+FUmQ4ONEBiDX1J0aofC|4zUJuGE0H1v?oWyra3JAG zj5?{WlYW*tmQ0O=0o<%l$<{0H?oPh7x#RZk(^g3lC=s?e7jOc+ zj4L2m1mqim(#v`&+7qTE95;XnerRsRxk!#ty#6ObW@gD<(aX57+F(G0h(k$rg5X^o zTfzqgmx2@EPmv|8W=OZ>z?$gle)^p8Qa+DIB4;0mtnZU+81k%;7gy5L1>xjQyzazw z)6K|9EzyOuzvQ$DF_b`|!gS?iy?FGqf?1cZ3*(bBt&@J*=^e*8{LS@(@ahDt;6Rnr zg&8>Lr=!eup@Lg9upr#$oUO2!`+A5t!%`JfRasGzx6K`t>28-+k-$UA$f@+Jn*Pn% zqw>!ykyNeB;&j71n0I^5a2P~5m;Eg_{~X=!srOl!yHZB-{K5jTzV}DeLd_m#M;gKt zdBEY;zfaJQ&G+w*l!Sud+W;%HzCMP-d)_@xU*B3rm|Sp=sW)^AXP0SedcA*qXnUW) z!=Enw3=u?(A$NOGnf2(nC&B{TgewF?{&?1Pi0MM^;CIXaS>3gmq+!usbxqrt8FYJ; zPT0HqJzG%kO_-t!0^;PZ0j9yL zrZ0NV|1e%^2-3rASvohvG=S%1;OqdyOCqReM0TUi-3WYsFrIaYZ$bY0HXYkW#oz#`Ioiy9;cMP zJc1`HDZ73L)53}zhYTqjyz27evhUwTc2)|eFoSQSr|C3revsua3>~hg_c--C^cx{* zN~7}ih3mZ72|GzBH__1%rQ7=N&!1#Oq${ zzSzb~=pRJgk=tg?oGAqQijs4bQFK2uhYSlUH7j2{9%yYH_Ny4o`?lW#(^Io%K5FECe zpQ|fLt45DokP#UFdGXK6(t_9-yIX8tI*(vUNC)pyD?YulHRxzyU_)2hhw=8&HSFWKw%Tc7Kb-B>#!WI%+31_Eo0X!31#&%B|t^{+v>&lvKoHTxZ;3wTdk1rNI5` zntQ*q?qTUXY807|K9hYDLCcEKCn}8?RQC0o{#-PkgboD4*=j@fneo3ZD!QyC0vvmS zJC`{dImGOBiW`(qtf%qqE~nb)WOou`7cyuOnI=+GZYZ)s@HPUfb4p z@@>$t;eKkm@?rZ&EN)1QX0)jWVFy3dZZRi?n;L(@158 z?`GIjXn{5&wgNa|^EoG@em{z?NXq1qu3LZpwMS}Q+5Mte0A?|=`G~n}VN_mYmzh#E zHe!AMZ!s@}zupb0Tte~#yePCd8&1;Wk@^?sf83s0RX(fJm0|a%J=XYMQBkljQg^?; zgPQ|_lOHw*Qdm*``0Dv%Cs2o|QM2ZDH^<47bHcPY{BswJ69o#oAxiVl$ z_6V|BP;m~x;yZ|5H{8Jy3n#r=b3zDe(CCK8m|i}VZ3^4ni;OzQ>T!poZ=s6?zBdj8 zCm`GuL=+eF@$=_>COfPD$UNVmY141Z=e4u2csjGd9h_stP74oj>7_2c5E4HvpzZ_< z8d&mv4BrOYywc^^O^S$#`rOW)Iu)a+IDs^r?&n=Y*;Aqd$mZyi z_h%}EQ>s9o`n9v_*DrIXuW&fvE82LvX%+1mA>ZbA4wkATa^YBnM7x5Nl~J`wQ=<#iC)b zJ&#A~g*+|Z5lc>R3F2_ln`Lm1Z>g8ExWGe@Cb3YD>R#fOT$B7RkJPWn*@+(Itaq*U z6&6qkg@o&Vq@qTWANdkE{u4x18o?0bAs-OqluoA9EAn7mx8zR2W98x8NC7112Hh>jCpNgq#ekPV1? z*9+?!c)zo@Nvc7yzM7gEo_o(MzaOuo9gC$;A|Czcr>BhJ86P>GdKgD(`$W98sN4=) zIFEW%)Jt{xBiVD`w|*?A-ZwKn%!y&mQKq?b!h9YV!MY73Jl{xsiJB z*N6Uy8@yuuq*nGkhbUg=FCBsr38a}$%Zc-$NhQ2ZVwN7s&kL}oyV$2kj~?$NH4nRB z_?}jSE@aa?IBTTN`JS79+`jZ_lsM7 z;aPGpk%`cR9tHLu59KcP`k zcROg{LT*5cO|T{jzMnMCXO=F1jIz!#e8j~AmoVOg^@59*9tsR!v7*JI+t75TcG~&k z<9tadOVG6{IcaX*D(8f;Eq()6UBz%MM+;N3&+j;nQ0og4$X<_lu`2iKBc7nFrr~GUa4UA9JZZ z!{nKyQSdx&FJcGW&gIQQ|;%bKxJ55U--+vIXHC6#1+Bdl(rZ1%rvj21QBI~wF zphcEvTFaEb%Dz3wYLz;DkX=BJy*n0;pNkwOp!Bs_1^dsP%Xob7Pn^zqUW(dgxfj7L zWI1Ab_8Tk0dm4@!-Xjfm!ZdzJg9Q1L($5sTOot<3=FC504uh+DV!~X_Nc=LCj zC)D7cXId{gHT{i!CN}BaNxk&aaU>xaHZ%PakLiD%qh8?A*9!~N&wISNdAeO*!P~bp zg3e6Xad*0R-~QJyRoaeU8|5Cw~rg89__V?J2zAm%Hrt z?WcDJW_-A~ayK^dWl?EwjRs11ApPd2+O%8Kt2-D?c~()+c|Of!1G1cBpJi0(7J_3& zBzEjRuT4o0@T`b}>R!JgJs*wmi%)E1tzUey&P<3xj$5K*p-07KIGocy z-RS#G*%gw_z zoZZfNmOtBjZoGw&$9ToSoEB?BPQMwp_P5h0wVYSB*>(EsMgy(a4U`}-%eNzW%) ze9km|)(sx_q3d-+ZN0t#{Jj1bA$;u~R#sNoefD-~ z{V;X@57tTTmT6(`iO3^N`WX4(>g!7x>`$^Px5x&5J4q(bibLJ1ZB-Lz}*TM!x7aX#FdXD-r&mi`uF+UOK~T z=FDzqTnLs`bJug?pGhgWy8~`>iu5i%M;b4n%$zezDm+Xxv>$T`^2SK@B&lCM) zV>|5nG=E-c0BN?`+S;u*SbN!VT%*__2Dnq5A}69ivRPkOEgr<8g4n6;T8E_aVGQ#& z-#r@_7e_T{N0RUDeAj@iqir5Nd6GZ_9JT)IFb5({Vq)kPW)kP7t870LEW&c0r=z`n zw==)ro&Kuhw&>X2pIY~Rd3R^4LF=0-US9S-yXbB!+tYOyFUU&ex!3CUf8Jr;b?|KQ zr0<^^q_-})!e2w(U}r!&mg!N4Tj-TM@N0Gr_R*e&DTSrSI3v%!p|DrI4$s& z&Vq_NX%2lofI>{NEzR=sI)99T9nf6Y?z&gyjzin=9$ zDYP;pw7+rQlVk3r9~x}2x3d|&`ce;2!QnU(MPJqhpPrs@dj;h^|4=sx;|)4^W49$d*YRo%A?xNx6cu`PZz(Aa4ua0^tcze zbbHGhUpEfc{rrAoGA?aTkc2C@n>A_TzoGX7LI7>6yxHE~a}RnrySmPKU+b;tN)twO zs$0~J7^z3U{c(4vKZ0nS*ib>WOm-#TbXZ7?_a2SiqW6am=q`NSV8C+q ztdTA*v%Ss(Bw>+ao__*`G%?n+)z&<1zJ~#qP6b7`PPOPe|96515AQabwr|g)FWEy* z6meH99xutDJ7s+Q)uO_>dX_Hr`xomp(JI>j-#Cln%7|@NL|`w5j}dho{Vq*5>C?Awi|M`Mq<6C;GyHv;QYte{JK%5tk?Fc0bI^^hPIL|k7mw)CRr11enU0nE8 zC9w(orJiTkiFhb}?6*~4qTr?v>zXpP{DS(+dVQ`F3Ky5XTED}4DwU_Gh26=`BWj&i zp7}J%KTZk<2CBPJ4dy5yvUIt5lyx<$r_T1QV@!^S(hI}LO zcDK2QOd$ANKCuu^OOGDYu9b=mlC-3l8I;^nNBO{!V@7IC@>l00DOG%<-TLNL^V8cH zl9|FKNQm73$FtdxhAgzU)gqxF!qX*qRNHGW-?Vwhjw3{_k=qL3vyT|DEAT<;KSR<{&&UcJ~8F&Q6p(kBRzY_mN=pN2`K4J)Wa?k&J-f$&A*nzGV>TYc6euS2~L@S$D)xmc)f1Vo=0nhU4HfUZ6bJ; z7yDgW?CtCo^mtEIaffp+3*qq!pE^PBK3#%F2)|frjX)2H)}I$oG9>9vveBXI#iC{T z$*w4`0459eo%i zRlE9&Z1k@>%25nd9S1i!(IrNZ9)#VbX%aEI$-1AthDSs zH=ar}p?GYL9FskcR#C9vk^)KU z2LkqaL2H$Mc*Bo(#x{_k0m^ZP*97}cl0pzf4!PgX`1|kJkZ5i7eHkwx<_q$Hi=KGY z%)sDs-aMW2qGzrBuCRBz--F^fPnN(OPRKY-)Pla;)0uB0_Uzfi6Ca9H?A9l&6IQTw zv7(WYgWvb5_r*AD_r1I85OPJJAYY^AWS#Vkoc`C&{KrL-ASDY1Ydz}+xcw@rf$Dql zn6wg+RL-M6?ja~btku#gk-Syb{0g{Nzl(Ox$XLpIW+v8O z#X#hBtKZ*RKRlkw_j9RFH7bSjml(KkW4zShprq3HH$@^9PG6EDzQ8M#F+7)*3I++i zedqGqVOVfZ$I5NPp6r5Yy=X%(9c8yL%Zd*`wSlXag zQxO$BqvaDz&{@ksG4?nK$Zb_4SR#MSewJ?hLen;ARjX#s<19O>yZC1&m)Cl`Hey3! zuh$CgV=rI2k$hULYn3z*jF6B2v-wahmt3Mq)iX>9n77~@%=pAR&7SIkUq~Aj=hQ;2 zr8*h`-Ih@G)mpc_Mf2bPygBQ5%9}48c0OD%V6HD!Z3u2O?iUs^i)wdT`Sjh@Z{fqv z-x4A8qkfsZsO0bqpKJu@J-pu=_&$-~l;E4Rw(kAxqwEee*-%8XZIA0viyXCd?diMZ zYR9x#!A#-W*Y`4iO9b1Ag~}l|S`oG<5MM3@pw!L03AJ!XrHY9JQc~VGiq=#r?x9uv zv~o)`gDkp@*GNItW+n-&;BAij;fe168i5jv5p8j5?$=kyprKW7Ll4Krd8UP4kWpu7 z+kI6pvzK&aWddo^;g^0^7G}*ie3Ou1l!CS-N0p{lT;|(cJ7ChP%Iu%6G}5TM<(~sF zF)wf9qlyL&4l^fC(Rurcxgn%dF}OY7nfHL3k z<|-^S5|59_yCg{p_>;f{u*X~_0|?f*HpgyxBG`~f<3⋘Lj~+icr=hU5&=G=F4lyq? zc_{@|$El5D@*PFUS(puB3X_##=T28MB%!3$)3f}r>5y-~73=|o*`$>tS$!$#0Mw=$ z-p6?ye!bw1K0etHs>Q)Tp#bOqF-gn*(`&DTjnB#SAk|POJ=!M(Ac&lb6L{S( z;sMwT9Dr5o%Q{jlB>f+Su;AwQ$!RSG)Ry2souQzSGq$oY56+$0Bd0S=KOr(Xn6|Z7pGLX8Aw@49)y!hYe@yiVF|k71%PQ|L1v_;1tP?`XO`_MoGGg3 zN+g08e+Uje(={bB8(iRHJQbSA2+0@G8!_$+(1>QHUKIJ+n z<}Un@x*#wR4@5MGutY-J02EC*wHu1R@9t*iRryEX{)zn1u7~<3QCsA;_$~wM9PLbZ zmdpdby~$gO-a@O1-{6Ak_J8Q<=y>mL!K1Z5wda>!z*FjEWb|il9?6M-*EcrWWPQuY z$=UI7d8>@{Rw*5+)Mi>t558#DxN&i_7jH-S9!A|H#IIj3bMuO;8nw(m-o{5Jne-sX zP)GgKEJ_fi_-fxYn%AWG7|&CDnn9wb{H||^r`I!VM(F*BBrSz@zl2>95C3-*rT>P# z^#8?MVO{I&RVuEZ`Qr~s)J1Il`2PKVg<6u-s^%7qUc9((4U`M6`r<0hU!{uegX=>% z<&pmX#i#q9Xnp@P{VlbTa*{EX0TA1JcWG)LxLHH~y=-Tn)$tQ=RX@^*F1{*8SDN`} z*uuPm$(_qvX@mc6Q2j5F8V1$RomTpIqG6kDkL@SO2gB~Y+Z>R&X~&KiMl-wSsjg<} z>FeX;vm>wk=Z*bvQ@O~DsrC=oS|<(Iw6?qI6US#<*sXS{PB>;ed+4ow@Q?XWL7vOK zF!OAkp$~iAQqkHjzP$UPw9@*<0u_rfr}9))Tb(y=-t68Q5Ou2hGJ)?FeXH=$zxb)i zEiJjm#V7T3zsB-$6q@ z7#m+|+*STq)Uwd^-Xg0u%HtJ-?LTg&$c8Up{8rGyv9h+@Y2YTe#7y~P+N+e1{;x{9 z>bR9UZmKtOzWgocWIdOA^Q~^(^AQh$jFNVAfWyP_w^X;#Z|K?h3+Nbh&HhwB_Wopjvlub33L z!)d1cS>cnXcYH?Do@xG*5BxODUvjId{4w)MMfpmbsoGlU=ow##zuvym>cJ8UZg^*9 z<)X2Re=M3`ux(H4X~pvibfW$HFN|>dB=4FYd|sSozI;*}*Zbsdb!$5t&S~U4O5RDE zeCWx7xRp&?On5q_c---yIj&Q_ERr{xYiku}^;Jv07Tq2>fq>&GgY-;MXK;E5v!@&MH?NFv)n388w zCp^1OM6}`2=rdy<2FL#JQ4RIQnBk+=rS5oO(AnI)^i1c_J9$fsw)$DvK73!G<{ulc z^By9!B5ZxZ<}>3)ZH;du3$Whf`t`l^FSc(TVZXg|N1IVUN`4w>6e#HVhpYtwE+tD#f8N_=x!q~o-xqpx+B)^Nx6h55 z+P&I`sa>D^^tX;y4J|x0G)>z+d%bPvY=h9LrO)2>t9a4>=GGad_9N7n8lKn?*-}~a z{LNmUPUUr)@W-^mJ z$liPF=FT18{Pz8D*+*gTdbQ0DkAJ22y|naa;ayUcak&G|@2s`le$!JLUJ%+Ao~+@D)Gv(aA}<15F;o%C+&6daIU(Y5S1Q z`F(kBSAz-i-dw{<>xbjoPq1*8E1Mqpv8ihK!}?rzgq@vS_tenx-SLAB+xxAP_a{$W zYhS)HUJpd7EPbqef4cpmK@S`LrP`x+4xTeS3Om%I|Em=z4jr1g?&XW`2{B*giwX~a zyN6x)*}f)up~3d+!x*XLF{AoUQ(4jU!{bL)d|x;Jfr)oGU%YvLaY2nx{hRuW<(pB; zeP8>39L#r{xqLB6(%Id0`A>uVVN+Ghu0j6KA<1uThvi;#Xi=$KeYLjFxBa!?T%EZ# z?ZV%_jkD~Wpqd2h_&WBCQchX_mm> zDKE9M3LWd@c6qHb_1y}Wf0{u9WSq%q_I-{yhME|texR3T`@H$kfK%KRzWcT1qt-5_ zy9&efHe1uML;mx}_>T62-~$gEb;(dGR=#BIQZ)3Isl9i?uh07r@$O}Rt9>1LFRJf( zBm3U3`@lYenh##ZybKSv_U&Pyi|`D*?dW^qlax{<4gT1Us*&6W4UlA^uZ zs-85;k&;hd)QHPJj8zAq=(zBb3Ts~fyWbkA@(QHdP+k;l@)9`$UjO&r3SYf~2a9q* z?(Ua!kBAiIj@5!Qq(1nc;Y>OzI{y@fHrkg{KO#RBH5IW9Z!a%tj|V*h7IN@2t4D>U zqUZqtBpp3O<`^`}SVyU2p|ECBJ)Uo9~kV}gZm`Q{=h8>!ymPgK4VHyf+m!_HZG+~wt0~-=M-KejW zi%^KVLZ>eQs{}~bOOh|w*~qAZwvj29>7m2?NQM3#2Rrd$Ccx5iFtQxg_1&LWraq(q zu=r{t$AgrTS@RLuzd7BJ%68*oAgaY z4+vex)UUe=1;w&fZDH$TQq&{o&h2jFlE5f%u6QK*OCONrJx~jHVv2o>t%lXm*7-Gr#j`6Cg*Z+cQ z0U|0oS9`#)h}EUZsMIOftlmD_EdS`+d2ORwj6~6}!|otk7F@WRYE09QqYJ1reZz~7 zPc-WH+lv+yCC0MplzK=0zU4K>!e_jLQ5Fj7(pABPwj%nfADsLKi01~?vUV|&*AR{+ zJ5yObop*lIjnoMNY$9!P6a=HzuRreu8M8(GYsYZm082CFSclBNRJJ8-=2nsi$c8P8 z(jVsV3wwK1e<$CGB&D(e^ecOji$0e8zSFNUa=wl7 z7t^WVmi`n|B^6Tq_wkT1sK-{%P1<9mfSEPT1~mj>0i)*P4XPhJDVQHK!9vO16Ey$2 zdzU{W58RBWRG^XFW`B#;k}Wq#5O8Pkq&5_45y^nml`mz5N5}!i`wYujwia#@c-t+hPFKEmBn~dfXIr zYO06X4#D~c_eog&X9Aiz(iTNDQnXd`SacJKu?sAJ=>d|jr83ldGtRw0IctPYw>v0O z!N-2oEVZaciwNdW4xF6+1pA^J+~5^b$kH!Oy2*+}5kG~c=7PSU+!RqKfc~UcFSOkV z`!J2mqRfE8%fFqwbd-!3BPU1K=fivVTC*`V8$<$UOEV9Vb#!P^Q|?Azm;S?a^Lhw1 zcs~>U@AZm|)rU|xxlhm{3imcvNZEQ&_Y(@)1*SHE4uq1m--<3alWv$5oP8{1ypA%!nz&!UXN?8)CA zbOME90yUSe-Wn5g(056}q~tf-XR$LlLBqVRzSB1;NVqlip;$5!OXKQAF0cNPy*h1Q zQt2c8A4RLIdRF%@MT8OAL7T}#r%szTllM3Vf6aK?EC8r!-9Mj2$h5; zTR$8qGgR6l3}RqClQ>XqsZj5m|qUplJAYO>|U$LX^|?GCVQ zSSpA1?hUJc{-nn{yc1p;OeCdQKz9BCl=ffCWc9TGC%e8RYrE3bTclZ0EUaGKeg=1@ zpQhEzaGj`H<6Qh#s1{^G!ms(;lZZqRD@tF-jFFLzOM1L|;&V}GH8|UL=;-T7R zMV1Mx+qz9fp_5j|M1zg0|E$k0|9lN1Y-jiHt5VCZb-gvaS0knTl70v$D6Hm2n*aQ@ zWt`g~Y3oipvwERKIbw^}Y|{5(F#__h?K)7k^FGVOEx@FxDl%q2>t6jZSLot(kJ*(wNxXilZ8RVb5W`%DW{*FK>p+j4Hnz&xI0K+ zwR+#-7A5VgVd8|O`mahIoocIDZtB`NsUOr-Ir`Xu9;!8E9BzHlzt67nKh0D3NweDs z4;)|5-|TR&2Xb;zHq{|YnL(oibYN?!FRfqIr1lD=Opn5#P+z4J;qi{Hu^`$TRrwN# z>f!3D(Q$F`U+u8e+8SZ3=Oh_L*Bn6Iv2q5!Bd1q91WzDtp4E=g*12*Jj=3}gcy=!& zfdren+LSO6J!xB0Vg37eIT|4LEsN4Y`Dzh1RoEH`j0`Jpfde4PW!yK?46&)r2Zda6 zr(5V|s_}je*8~Jbb_aj4k9GKM%X&?2N7d_{CPEI+?m3`<%rHsW6NwtzdeM-;q}1X| zMP;~}UB`JoKA-AGsVQ`Zadt~#)-t8prR?KULv@LM(OnmgE_#G|i@1cLh?$CdJj8A^ zo^AJdAbcTxexSZ5{%Eb5I6r&QMgekLri??Jv6B2!3iMCQkC%>+kCprm`tLZQ^aZj| zGZPX&#WNYCIp~|!RTHBm1KSUnq3)Uun-dQwC=H^k+e&o^8`m`8m@w}tv0|;F?8}lKm5_o_J&eYdxdSME?x2_Y%$x*hR1wJ zymry8>rzF7h)c^9VKMX|8m#m<<(r*)u=iM&0BLV0tE$iIX9RS395fbB82^A(ty5FS zLtOr=a=MT(j&88WRJp>Ij-ny$_uOkX=6ZkRoLFNu)YWjC{XaUGLDRthB0fdeA<8;T zdD-0(^n)V_6?%gxQwwBDkdcl1@^m>ZU62|R&Oc0jWrummzWs(9iBbgKtAp&R25PKN2`SnBk%&lx;OxDNjOYYQmwA0b2QN5Cr@}?&(cD$)I!yooM zwSL3E)PRJXCkN>ySb=bC&`L&HNaQQP*dcnT zG?GCS^&SMB3{!dNzf$>`2m}b^=y$XI11S6<@&eQ4G!P`TXC;x8gB}px*ngtY@SjiG zJ2()S4i+C4tmj<6d09;!u~|C(?S%$J8=+*2yxN4JzQ|hQ6sA8&yBYxLKW=w<3oU$b z7atmFSs)szP$O_-ORu~|DU6bQCarL0D-yBm*Dcrq7_cMx8jeUN3--mwWBgB+VQFd@ zm3}N+)G>7&ihO7~K7?Eml1x+}E3Mc!gFp*GDg-D4b8~K=#ic%f43cf@#mqEmmLsvP zvx0xPx3nNO0Vre#YZ@W}c`s@iz8rUts|G`-qmH$R^?0Q)g~twhz8*vv2OSVv>GU?w znfioZWCe5-@aSxSL^2Gq3HJ~;p*o4eI1|+h)%serrXVtvEx_|&{C}hB zhog_kB}HaB3J*KEErL3L?T_yiC%$=+O*dDsI0xi@0M(j(8@SEj>ODk4PhFCu3d2Fl zy^#98&p^QPE-n|4g(`PWiDoKg0RH2ceGCDfLE;?-%91cTB6{noItl+?t1AW>de|no z)~y-&_ke<0Te=S$ zbs<+naqtm)%LQx)dODILv`EEvZL>RES$t+|?sRPCi9;3Q$4+Q%zm;b9KyzaA^vt9P zYZT8`RY(x5HNDt#f?^7yM7ku zuG%{lJ@d^AH!NRO#DBl zwM*4PsuVvR%n96&@CE3d0M-W{G5FiswEE3#OfW1lz!ws6ai|WiIKjAZo^+0|O@hxZ zd2UQSz40)f(e`sHdA=={{vOBUOiTZ8G)4B!~WJu>A3m2sH~vAVBRCI)gx zR&CNhJIiFre@{|IW>jfL-0sX7+k*=m#i7TGGYG{u$P8*LQ-7J&*%;t#r1$X#Qcaad zDScgW(a}N=+leaEEaOLpFGP}DqSGtg*kPE%#W00OY9 zQ?Mx^f*k1jC27(@QS;x72xJi(aPDBs5y2R> zB4ys-eFg9+RUFGq7ZJ$Z+>EOs+2pKPJU(e|80%<-}_?@U+`4_M5isBLZmWbS))y}lz=uXih>XxzVe?xAA}+j2SFsjHb?wg5IeyhVLaK)U`tHB<3x)yJA0(S3>~HD5GWnAy zmDwv@HSi(QcYczQuYToOJ*HhF#*up#lpkz!(|uK)w?^w!$b0?%$9YD#@9!Z|w~M12 zNB4H)7yFS?BI<%yMP$QQ@X?dW1X{QtMih{KaF+xGMQ|;Um(@qoB}f*L-pP@;_p9^o zhYdDg>d(@=ef{+am}>J<_k(Srr^7E zr9se6m z;OcK)J$JPZUIC`@ifjVlEV!bnzw@5LJ|c|?Fm)=HFh5gidJYHg>_@HsQllHLb7qX1 zmAB;$1DvK?A4aFIAh84?{K9Xp1Hz_)_RitfnOkH%17bVfETg)FP0}O%TaP%8F2Qc| z`t$8el>4;JYtDUsgGoGwmP|XEBD!KOR}Maz`wt87`qOO>ou`j)_13y__FA5+GI}xghD$@; zeH~l-E}a~=tw++~Wg&{=2tY&v688<10C0~mSRs){Jl*JXnf}ceLH{fCQVdPO#yYa} z%@y{3cRl_66VCJF$qc1ol9_<1p4Ja6{Rg21p ztcm8G>-w-Ah?P0hP*miNe8-L3GzI6^#XXydYkWjRdW8BwV84`Kg8R7yv!u@gULy7f zDynaP3bNFS`}#PjbMT4s*r-P~wa`Ecw}0r*ukRq^0v{=B3^RzT}jXF?Qc{*bZotKG+XV% zJrbC!#G}`-_22RJ{7}!7SrhZ*e#+lS_jjGnUD6fST0D_eef~J9j9f|XwRCReZc}ZH zu}Af0IZZ&{-7l}T9dRrpdLXS$(CO6@bpn( z%c4(Cm3+0ZbYlYp*6l&Y##g=nSIm2DU3>a=(_N9JbBw_W;YYjnj6aGchx*gVclNgq zEvz%DuS~I)F`m_UzaATFRLZk!P5SoIt56L2xzc=!UfHkix>&(OAp2>m!O?MXpRtOG zhXd9IBA!aFDq3EUzWxYzx~|dZ5qq$wwz7Uy9aPhb_b{A@yU6_9GSD*0+R3&mzMjYM z-G<1cS;nubjib3l7^mN_8ym@gSmk~^$42D&9~|d%1#2sBSH%^rK3y*&u8^3;wV+Cy z3PTM~8sVx@QyvQPb7S?v9;MH)e@SlviKL#H*(M(oGO2)Gtvz@u>|9&|B>c{#j5llC zIRAzxLf+_AaJhS1n&qp?n-b*pm6o;fXrKSmyS+_2%TyV+=lPa{E$Zp-H4nvvh`G3up@QJRONsg&6J;xl=4` z&eaN&qW)Fg`rs{)LIim^SuiPh$rCTCF1Tk8>{=yZWXgOoO3>an{nQEP^{*;T&s|-6 zAR}BVcYi=r3KBr+;i-Cw(@y1wJ>TdbD@-oUQ;d*$;O4$*x37+?V`D}a$DaMPDQ{qR zN#zs~G-;IsiU0mK<(50cq+UY`4MIBF;tD<{^yrcRpM_rB!|XeEJCHwIoDVm<;rd26 z%l>xyscvSkd_nb0hpfll+l*35^ImtAn{Pg76>>k!w{y-ZH~Ol;4#S{x3nq^a77E!` ze395)pYyE5+HFpUbtII9K>@TwVyuR48)?`<<(Yw5XHwd;khGgXQG_aWd7sPL%6Bbi zux2wd?pU&+66PbX#Z*{aWUwx~i{s}_{#4}vsRQ$8*#oMd8fDtn99EegcW!K%Zqa_c zqK|Q@VC|U!<}{AaY?-|;g-^_9M`pJ1Hf8>@jxy5Z)-HIvS1!B%4tX)C<^Y&Q;VYq_ z@D$QDM|h>TUO$M6@d)PkXi%c^@B28fLeDi@^ zph+-IJ3P!wrBl5n%qwU2FB$$F+s+#qT{nuy027kB;^co?{)d&oRuzw=$eT~*rl53k8Sd85tXj&yv{ff=q z_5TiGUFG(-n{NFZ!irz?lv*E*Oq)5603VO{QF${;DCmp?f0K3V`5V8ze0YXbOC?!cm2eqnZ$!6%e>k)v(Mk8uskBej)cDzJ0LzQuJ27AA-(V~243lVM*=fApZY zN@HLLQ$+P22ju@gw~_DMwqF?C&0T|2wS zICNh?gyI0Nu;1|JE_hbFy|Zp?b!EJ~SWl`byG`1*ilwBiPMbNB`}jy@Oiy@4kN(+? zbd>^;7+-6NDkGN%`s)=QccuKbK9~_^X%%|^tBUaChTs8(p2khcQ)m5TxF z3YfQqp^1M&I(Fms{Br%HMn)C;$uE~Twmupz$*77s!h3!9Zb!51ieHgZPc%OiAIY`< zqpQ;NGBbr0or!gvipjcd9p`^Y?9%UkYV>5WvCy&7>DGz#74BE1^837)85FueNHIJw zJ=lMiC^AXy*r80Dnl0?a?f?Fs3aAb-?F|a5{+LTc!H$uO)qNUkan5YXu3h(@FIh0; zZQa$B)!*r?T4k+sdwa6+hnpuz4HM$KFLQIxent`57BPQ?i?Qd9slB`z^T*&9|m_2WfVRJ^}mu(u;r&bkd?7dLBC-; zDWE)%+AbF%>`7LY>8h?6ct&ScyExbdo(3II*E-ow=P_gZx z)zg7oEo2VqrMtWYZHI3So5mdfIux+5!`1!(GYbJ$fcU_o%0|TMNa{^B$qWx?CKWi1 z3T|p}U2!cWIFrCdBb`xknsolb5)szV|&JU#pr=RAOgh+3=BOTWsAx<*d7u~*)c$BjwmFADk+qp9Ijklg^=)C_hUxZ_xZ!A zW>W#Pd)287J8CZFU!e{02CohP&F?Sle?Nt~$sx|P z3hPg#3<9|E6na_E?&)CAUIMffIBy2|CFQ-NeUDP(^~K9Kgh!bXKXI_Bh@d;p2l{F1 z)siHTut~eyhf)=Yj>sjSIs=mZ2h<3BPq))(-o`tFOeV1+Vo>efb7)o&6DiPO4dUNSo{x*Z_C1tsz$uTJ&E=tl`uh5p(9cFLN(xSlA3FWC zeb#L~0r%Lj?N=Cr1ll)v~bt>>oe1*JhCw z;e5y31$=n6EEQ6h${*(5ysvDDTgK}@ayXRR zb4YqljXxCG0`uUqRBg=WG)X@QKZ&`0-s{&!gH9`OWD~V>RzT?ML;V>bj)g;|O^s-95MnlK!();&Cn?|FuWv1SH|Fgxmt3Nd4E)$e_ zT@Zjg|0vo%KT6C$iRz)1l?r-Momc+yZG%$Qi4(J2D@k;;$Ckp+!3u|H;d*%$V)C+c z`B;m4F$OspbBH398n#R-x}UG!dh<-1H)rlDiEY{{%B37FQ;O^2f{K)K;EPwWO#ZqS5*>Vo#((3P?vj-%B0^OM@Ewdl=a$ z$?oBt5aZH&ox@C+T7b|!5jnR9{afe)qb-kFGmI{j zkpKP-lr<9oFANrzH#!^v)CjY!ZJ5Hw$H(XV2*-$`2^FxynGo?yIL0@=RCD>!I^{uB zim+%fRDxez$FK3%KOE8gUHqk$EF(AU2HLhVx-V}zcI;#(jj`BjplIPsY0wirr*wno zo`4RQ`F(5kEGTb9Bh@>rwssB3G(ng7B zF#DihtqlC@N>~A!u$gl+GMflSXaEBN z0CEQ(BFP3(w7{M(5fhQTs68=oQ9?8Q``c>j^n0oNcCYh#WyWZ{MOq$$vtkc=-TvZIj^ma4H0WY zW{m?jq^VB{06zT_Cj{`?7?)ikBl2~Vu^hbT8R+S7@E-(F0~xp>q|r4C%_1r`3N%wSnd}k3MA{;@UkYKmQm3MsQ1_wrEJ1V%ke8H=odnHGG}#Z^+u2XDDSL0r zpX?J=>ETV$+MA=+m&7jI@oo9(W}^>x0UVF(H+sd@*r4xv3Jgcw1wwC7(CPO-9J3*j zux^7v9$ym?rS)3y^i|SiM4bUx0YNIj{VV%BS476>oSsU&03#!>=)sS>r&>-XZN6l4 z*E)*2)L=4c&v|3p>{&^>kZk0}IJ22uHSwaMJ3zWU1QReH?SvDRs9lnk4^@s1I~M-Z zR7^O@tj$3hq9>aL3j>L%2y!;`hh*DvR}y}{F|xT@EN?i_r{j;{_tz8`$X9QQhy6^ z;_~tP$7@4yxN+bIKWemP3xNI(sVKCiMK_ixPYuTU&1>IvpHGv^9=)TN#lM*^pSG!$ z^)UBi0;=?igLf*Cw;0<1tgGJS!1k=BJ)OIAIy#}}S8gK_xSM1n5jqMRBi<3pDG+4@Z-|IP)4x7AYoi0yTnICa? zcS)xc6%*@iy26~8l@&pw-I?_)obNWD--n1E`Xu&ZgoaG>*(E}3tSXvMDhy!lo||#f zWiace3WM+U9uC>W#0$cB8`$5!B&3=4;_RBi3^Ie59f{uAdM{MwQ-kgMG}0KO?>HjP z_8EpU=Lna5$9Ntxkz3Kx6)WBgSgzt#=*&nlC#QQ;wkg@8P0iN6E2TZ#x*xLh<^#KN z@BHc53TxtD`8214QA7X2g$t@r*BpD}?pk`M;iwE8(#Qma!6&D&sYwJJ1QaGwZt?&* zIyh)z*Tk8a%wC42>!>FBo&~KxlI!NgXv;*SCZ~EH%9(|hv5ZIWzN@_m!+yKQGZ8Ko zYM(>gG4b`d#6?GnVBJ6?ZtuRo&sjZ-x0;vE!)A>zuafdrTOVz*!;ea za@(F|Q=<>ZMxk|h)MA6rSILckS8PP+r!Gmb%RKX1#is(t^-(si+08(p5qKoQj}j<> z3Ke{tgtiTZQ~oGXIao6M^;EDD_i()fv`;$v1;U%6q5WzE{Ak0oW^}7PUi;>hZp}q111F+I{k-?`o!Z#MTh~ zB~Qpl{0iW3gd2M7L~DhM9wRSp6~QeKT&v!KT$D6|MX}ZFM|-*P*NS(tZRIUXb0<@- ztJR7I3`@vO=|S9)%w5U%kZ3DdKX#cjAJPU6Hf!l*mlyTgpE=Wr>Na^s3IO3MtLJAW zoZh;v=1tKomw7t8H)D&q`+<Zp?nVHt&C&soga>d&}G1S zhMWo1;0i<*xX1yCe3LlGU^l<}66kPW7JXr}OTVRjDWXcih8Y_h;|#txG6gXu01r~S z2X_hk6)hcJ<#KAEEiE(UHrgWxd7NzAN?I|_x*pSMipBof^QX?gxf+?YLyUu+Gj3*8 z^331A6R65O+%pdd5m9mlhA>VOZ{G|9u^Zg; zSI8Vq$eOl4m;)Cf=q|IbW*Bajh6u6krI&rN5MX++MM~;01}`zNMf;S%&9uxFLW)FH zQX;knKJ`%zuEE3GP*kE!>v&Jg*-zwGajD6p%UT^8kfQ*ASQUf{hWYGHiCugPZOXY@ z9QlITWHRRzyA(O(Yn}42sWH4Q3;N3nbRXz65XyvUH4fzX5&ibj=@*zm6EAC|-6)OP zHyRrZK#0OP+mTC|vf&iqcmTZ+Vo_x$Hy76zT>h?bV9g~M-fLGGby|vh|e5irLobPpgM)6<^y_e+Y;j7c`B| zeG>Jpu`z%tDza;08IAtC_VggzrcDhvgGq^o)hV)LM|hi9Jxogz(fh{odF-*-Qww*5y>{i_J;gCS&ld#iAUIH4iRdxqwcv;2F z+khw*kjx%It+WIOsu(>J>DVksg=t|058CxdhRea-{lH!BQ@H#Bva+ z8zFij;s`Obs;CC)D%q$%#xk*HUXIbHvtbKg*3Nwqsgqk+qXHjx5-c1LLA617Ohmcq znFaA~B9K#bORx)3p%GUIv;`hviEeu35l)&|fPAfGIJ=SPg`kq#*S*02DL*VOg%^J@ zq^R5}*S1wONQ=M2*Yf7+1_$5D0l;(*uHV>ANr3gJtu z-B-J2*%djrp+wT5duiMhKE?-xnl_m#Q`;nfUw|DL`s=Dco`=FQ6PFgJik+|vQ5w^x z?FZNL?{xaIvgXxf!-m^t$wem!Q08}xVDv*X&HE6JG=WE z$+-ITcWHtpK+b`}jDJdpFzV(2NEV=4Fb0Q)LTg3h*L+KU;d4zMTHE46ZRg%4YKVz+ zQ78IVj}kMoVz8{YPqyR>d3wD#v<;jhPOM-^pj2#h-|O$z8Sz$Jfye`qkj8(6d# zP?*AFe#YM?^cA=)z|IcPidZ!uos@Sf8K*oXrw1gNusXH&OC0MeKP`C8&4w*A#jyPF z#p|2*BG`yX?rgPqisBj6g19Ri+g#)@c+S8&e~gd`k97PDIZ;3+JcjBQrLC3vr%?#B zYc2W|iu-pHJfYr&W|VBU+jrmz?wN1jlxv%D(^7&(E#Ips<_RDQTaq07={uK<$h2r7%#q5M5W0#O33sMCIl6W7r?FHMYjW;QRB=sjtKAWjC^N9A~Sn zY@O_cq|0kGVkJ+1t5-O!?TqGBERio>f1F8r*>h@X%2Jv!v&u>;O~vZPhnZQ+JLc=p ze2uAVj-Kr2PKYR~ZmxY(U2R)X#TDD!R}3s5>LVCrD(xTK?+!mP;*M={wrDc}=55<1 z`9rQ426>oL$Fc-YF058#h}yzmld+b5em0eUmni3C-%iLdlOyKP<&}4*j zjpL_;636WR$-;#<CXSW zrFJS&C!r*GGMw=U42wu}d5eboZJGbD09&`ZR&CD~=Hs*al+cOOgUIzQ;visOd8pj_ zdvkO3(q&WL8yh=-+r^e}8bLB-VHHX9a>$~bEdPQo2M^@xrAw!ZfB*mrx6dqF zET!j)3RROa+f{L5bs3i||Ex2IdaI4_vnzJ4gD?b)iUk5rltV zOlu29Zeq5t3QgfJ zAVWrE-xi02P_7g|tN^cDk2Bb{DpW>Z@#%c_Q!PqNyp@f~S6GYN2z`|BfS@**etVly zM?~+#jEu(Cg}GK@UVrn4qs%^0e13N5hQFzrGB1P2@fW{WT{P`vVD|O6yzur^eToP_ z|CPimAF+1EL8be(yLCDQ=sTId&_NJnuo`2^MsXnJrseIftgR-9<21KxI5oGJkL2Z+;(bMW0k4+HT}r; zW3M#Hj=^|52?_@qULogtKlBkQhUY|9!qRFross+O=}sir)h(w1tZ z`>j*&WyZYbYZvs69BJq>Z^UZ@8i~9%h^J4T=n7eNf^zN4)fFpOc6RxwP)E;(ntXJ- zAf?QZ8`M&waCvrW$_@frmhKZjw>tjzrLlWD3H)MWwL<;xXnVk=eTpFfY48&+ zj>pKpL1Z9{tfIN^g>$h$QsYOWMH#2=7^zc5$Xj#~{IKbk{ln`#zT>kJrmS?EVM7EJ zufq@_0ClWCLW>_g+wq8mS=GY%@eCnX)zH3s-d;|Mil9;z4m+bO&+AX~T)1}um?$DQ zOGx>Gm;IXh$A5v~;Euw29GMTS$-7t-&EVN5w0a1x#Mo@JCtu9{v)LRDxBmX9YJR0w z@fm8J6&&0LF<~K;KLS@l5)d<1b|KeHCBAYJKT&CJ{cQV~xN4d3*I>4b$k#n}=?@T>dy z7qB$w=htoAcM9fd#tB1nWTiUCX#GoP^H`8Fae>rgL#myvE$fc~p8BW0Knc zBewU9khvOJLEQbznL*6)6LFIlz46LHFwjDH^3C!&eJY)o2DmJ}3X{7oFZ^wVH&?}d z#e%BtPv}NHaqVv);9)=+Zi3ku#TZQUMMO&qzg=^)OpDgzI1wXzp|n>gA|XMiVdynf zrhkIgQ=eThz8wMc!Y6Jo7nehXR)N(?INME48b7@go(Eu`S}^9Si`k{yb1O$hb?T?> z>D-IQ1=|mJm|TCh;{?G>4|??OCPKcq!ozp;g({-Wvcb&FQa?47K9O8TRPp}NG(QWg z`LCufE%_JIxmA^pW?Bb%4qf5?>9c&(#}}vS0sEl0iI-qR_~i8OFnMBf&Re5a{Qfjv5eW%>g0cXf zgwSh+w`~j7rLb5TY+U^7Zv|Rry~4^-)up+{7v)706x3Z@UI6a6f`e`=^lt$YO^Cld zVMG|sR11m4XUI^@5p(WPa_TDd7(}1>+`Tex@0G4u0Tg z88CWc@K#mJL0*QIGR%#L#s#4mlF58q8`x}gfl_`{wP0HD3pF+Y$yHv>j(l)(1Bz78 zA!>3-lie4>zaQ^!?EkQP5UxN>_{8QtdrYu?S;>P^+R^aR@K2qmuQ(m~C>Yh_SE!88 zUtUx!!D5G?r(S!zW)B^`Pju>a1bPOc&}01DW6R&(VGdpM>%fl;$@4R(cP;ZM}98^q<6ay1wU}2~62~nOX z?k;MNqHH!Fp(x@e$h%!7b2^bW^MqEQSX&y#xgn&=sXeFF+!liY2q4Q^Qa7SiJ%cp( zAtBXr$T%K4cyMJBMd3ZW3d7b0TJabnS66(Rl)F$ zGe7Ok|HeQbhRTpgD-a{WTvfMoJ!{0EvD)%fc8*G(&%~LsFEydTd|})iKAiqa6mE-3 zVNi7_9P%$s&3dWIeippJfq@otJUkT;EP!Y$A(=v>^Tdo;hEk&CKYu)$_g?DL#4=?~ z6Oy@&l& zlj`aO@8k?+v+R0Fa|b$;-PhmUL*}!1qT}pX$IY!HT(q3Ja;1Tbi=;o^b`g`Bu~|f8 z=jOoBQ*q;0l=fe)K#TGv2`v3jvSA>9Q`dWv#+2=pgcuhX*1oYY{rLw-%S2UYdW!Ga zgO3z#4hjirAUPj4rv3Ctcc$^QJB8sGF9Y&&5eLyxr>e0qB#TA01L)* zYcFdnPQ6`oNMB!tr|7k><=%~pOJTp0i7aog5{I%$@&(85mLY4Ha5@%505?N8>aFt= z*&s6>$;Q0h~@vW*do%$I6O z)5z~y6ayi|>V%okse}x~;h3Wg2UI`b#4>gSEV>A1)4n>lK}%nJGRhjf?>y)!6E8u) z(;}5Y# z?FznAln*}A7XN)duvskrLQ++K9nw_i zsl-p!E_##*YXGJQ5@&3>*2|2r#e5Ts{<&U`Q{VYAzH871uZ&-z2u8fKs{4N87s));h2M6il)vTB(G-O19`Se}E$b3-Bu3PwDa;%k9ITDo z$ZFR05RH!<)nBPRyD{ZD{SaIdSTDD)H2>H-_oEe7=V3|~jBh1OBgt0eITdwGH!6?T z)7|Y|a_CWvy&1f$6S`+45JL1T80dl)4{e?f*WHreCgha!?K>Qvbd5)KytJ{k zUHN%h^eXv2S$IdKq457-tl~CDF!iifWUPOH)Pr`=cb9h)ZHmp;^?jlPK za@t2!RT+|ac*Mya(5y`+ve*aZ_tUKQZlw62^j0GxJ zcLjrI33;hXVeF?bnVLk$a1>czxhTLG1RAC{ z&EorkAt5$h8*zMoz2W*N($+)RI;7DlNzbe?N5m`*`y~J3XwH5*lL#Uaf+zU-c&K~| zI_ency|OS;6ka?YhUU+NIi{)^o3D)Sl&W{BtFEq2oDpBvW{whlaX(^KNc#LrXKQ>< zUBv_qv!>;2r8Q?cyx%#9ZAFdK80jSI}@gZk(aMn%DqwX08&&xDl&ut zAy1)Z z*C$Bi-Ov{F^DQh|TtUKj_J$tpe6w7t<&v)4kiov1qmQHFzFdpWI?(Xb+F%n4LUWrA znW&Kx8xyPhfZ#oZewyytb&8s}{Wh*m*(g`*N}KrE_Y8?$t2{dUr@Va?<8>{mcf2|3 zqLorE0U*;4CSiO8PWH$4lB?t2>@zSO^449v0!m9i*O%m=0y(X*FB;1iw8HB*yxHxX zV{GZvNB1{V=mXb|!_`o~o40v>)S4{-U3Fmh9zb852;*6(ur02g|Ht< zb?H3Xjy>Vrz|o!a^5qcFO0iEr&+9W+u&b+!kQ=6_Yr+AOsFjR^6@C)DYztrNBo9KZw^vpBtxZj#b4MnQ7al%3 z%Y>D!r}@EdU&@99nH~dWu44(2ji=&I*N={l=CVv6=wJSKT;Ac!#JI;6mu1g@xY@kr;|I3$PG(udr z32hhv!?#gKpWUG8lWs({@oII^lR3ka?2fZF%kV zAC7J@T5xWE-MDLu`hrG1Ckk;o2K3&T2%Z3V$B*!{feMYXuwcpRWISl<$@t+aWR~~C zZ);_$32bryPru{%6{qJ&w@%(F}+D%VqeI9Rb>l^hcoZ!g5Vx@t~rN zMwSHe-gxC$cd~!I5kCv7{3U-Y=Ogy{z21*P(30di3WtxQ=#7&n0qGT2IPCfB(sM4Z zHgVfsE?=d-%?GG`Zx#R2udSnFsIR|Ph^F)r0uRQ|t^5HzCanS7_er3(Ea(r3lczZB zGpMCX;h~AkQF#ujs;T`lNSKNIw_IlUQd4_n#p1W)F;P4O6%@?=kD?f-GwlEcFEq&) zdj*eD-2cB^%l1QD9eF%Zj}xZj`Rb^-CZAi4N~f8Nx{V0&F?feb!(d&0xRiw~e;{Kt zcnna)`!O#56$XDQ6z>bD2u{I?fUwCBsR5MSFKhsT6YT0D9n!d@qs#~Xn^}RjK_FuU zCW?_A^}P;^ZCO#!N|tpFyU9KxuLo=v`l7!ZB4W=J7!jKz3`Ysk5o{0N;T?_#LUoJT zRVW5qAVEWg`9Fi0 z@$TnQ*w#iK)T}oSinG6o`9cPAC8BlsbYQ@NKHB=Nv`YD6g2<4L_YO4#$bfn{)90q}hQitQG> z7d-Ls`o7IkI*BmbdYIBB$GIBbn^#y?LJp#+Yup{Qv(%ESYx-fC0_cVT=5?6eP?u8_ z_)wnXthIwa8p<_v#H}8;mBD&G9TROb4Pl^oad2}RLLLn$Bci&5NftE5s_ae#?1t<+ zo-uFsbGd4z|BBIa7mW!1fznaYu?jilamDBi{T5LO$^a_M0;+< zGKzvPdIPs$Innp&0h(za0Y;*B^ONo-{4RqNxAW!^ zxSWSDNA5xuc?rb!;M59G3jx5XOw*9aFg@0Ce_vKcIbb_O&xAh7uM@+$nEsJBNRw*-SPC z&Rr-)5hrDI!HVfne{S0J6nlrv7g$(W07YCe&7}d_+jyUjm)ygUQ-FsNn5ge^T**&1 zE-s>cMT8h2w}l&lsqu~PhLoa9f!D5mLf46ifq^YZ2u@`R`laZSRoY~oLPt+iWU05}PCOjq>PAe639f%)Vj`>xUf>}s>3IDiQp8&V zd?C0cfHmS)!ZEABvxX>$k}PFN9p|YldZYFj_QTig3szh?=OrjIph@lfi>M(XUwG%g z3gL7%gRD9^*8@Z~0})kFP%sj}XRIkaj|(TPt%>d*;a|d@0so)xd=$ovq@6}`LJDmQ zM1p}8fsu(QK^k-plV@=3D8;*_DO?iLi^!n$k?-NX@ZYIg_oD1Iv~N)KAfW^O*M9QP z50h%FtfH%gwFRRRVy;4VDcX!RCn-w$I0zA^h+qz|!2~$bIn40GsRire01AW0$JsY- zB<%t!rLnkk7&9{+$mM(k5lz%A{~>y+f6h>Ox?qlFhad=r7y!GV)3h??IL5>?1Gb83 zLql!fE`%=z#5R_*Se>x10{8_8J~4<&VO#`+?v1k)zjWeoZJKuoCr6&!@I5k`oH)00b@o&H_U9Rzbl4e8qj7o=~?EmXR?8d<2U)MSeY~ zn?RH-{jm%G2w3Zy4O__>(8T==xhP_VJ{DKAqfBfag=&PDMUEgG4@6oSudJS{gqUDM z+$3?g3|8o3u2yshU>O(Cc1b7)2nt)AK;e%bWoxHUH)5s+2nMmGft8wTPxVG{1`YBj za&lyeLZWi6cC%wPapN{g#4GX60QL8-qSyQ{8%Yc>NkW98vnhC)Qu#CECzUldUtkai zVEE@BKe&c=-@Fa{F32j%7ZnzBrXp7IG(n;ORfPCdV;4v#)6w*Cs1T?-STMkAJkHLR zu`utqRT$lZPZl}=9RRHXSRIyRPEQ#jFepss*7`TEv02=6 zJf*Unt3fV%3?wVTSVO%8f>t<~)MY7}K!=`03|_Q?;^QM{(w(aDBrh>!AtVoUES#GN zi<5T(-~}VTvvlom7EFn#-SM>)K)rVD!U9DmX`rG)kI~Fa2p$smEF=JzYL6X8*8u5V z-~8V}Lok@idmw@Il&oJ9&}!%@EtW5h4<9`$j1U7=>nsBiia|dHw8#PhL>JSzh6y-1 zpp1t&o0XYZ3)X882TPmBRC47nlIhL;+0g z2r>o$8KH#*MEhP@3XK7^1uxozl&Q0bv{)4+hGD9Mv;zNv1-Q2CKU(!k9Weg+mgkxV zVAf+;x1dG!2$VG}z#{8>vm=3IaZNE0z#YM(!Hn!MEUl1z<5RfhegAz+5kfxJ9e6aj zokLDe&+#V!;~+*+=vn_sx&`l+w0}f@fGl&&=m{AW@Gm%s`Yi$Jg4}JA6D* zkI>FxUQLvdDM}B2_Vwuj0Y|hZU^kr>TUT0Iiqy;GpD8ybYT}?K4jkZ&VF)UA3XNH^ z`nGJ*ca!C|{O7&#zD3G`6coxz2*q#mHrAlmgn&p<@CF;4fn4d^;~0Drd=TiH$RnIx zcg8?$9nX@i3+g&JYyGEPkA-~@cM1hQy!STK#c2eEwieT70?5R{D*|&#yey=(h$&$Vxc2*hXqZKLCmL>K`Yqu(xj3AqQ0A)^$%?&I*5Cy{S1)n zzt5BBMAB!JVTfaR*OE||1>TOHUi`tok0%Q0)#da;8R91#BXtlY(5omK4k0&#em~Ml znw>WrYB>}nxC-$7_z*6Un;`4O#$e>7Uu{pNvtVq71oO4f&;`{{W}Hs&(Io1b2t-Ih z8*oSx?L%4b%639xLt#X61;}&)-bXsdoD|P`P;`kBB&Jjp8kH3IC??$XxpzuSAHhB+ zP6ecmiozcG7!IJ3s~kEU0;3_}~stT>4t ze!9G~$4P-w;E@YCuBXT^vHUf$nLwwzS>M-Xt@#`)fw1{fQq=HkgjNQ9Od?IU96J;7 zg(?kGap2TrZ}x@+1?l1cMC_0R&a06Is@LHjdn7Aiq_Y9f6j{v;ZM z>GIw40ThK0;!*(>00y7Qd2J;aLnvbR&`rjW+!HFZ;PIlCK(Rt18OUEC828-Q;sq@M z6lfxM`fh{yXPh)A*aC=82sF%<7L6XF{NGst=%=St_#WXK3Cd$MZ`bS@@&*vt^(7}% zaGlqthT*tDQRxaE2il7;pD@9eMFQZrq-_cEX_cbCUK2Y{uu^9Eq1FZU^BsqMaC{wx z^fLkf5~F0G-cTHWLbWR7a;?e|%nvM0az5bsKe&Hic(Iz8^~XJ?!6||Vxt#Z-7nl%2 z?6Wm8;|Ep>Cc;D}1ejIi1*}-HSQ06>w4dWY5UL=HdjKl~xLT46W60A^3ENBrQFC*n z|M@mz*s;7OBpjtZX-q(DG?APn&`3pS2mP;IRVNAWfXHk%F3wZ^z`*_lAgwL zsxrWMz(Dh2(nx3V7%_Z#*Xrbm?f<_GV~S+*y2Z6%7?>cy!Z)=6ywWb`+(;agi$%SP zD%jqDhOGbygA%ocfLXwHQ27;wphgmA(qu)W;}8-R)IV^T-3GMnz8y=ktqI{C4$}s3 z;KpeT6>r1EN=kVEZjY$*c&Pb8j=Sk73hSAfiGi=5%Q6%dq)a0s)pd1xI&+t2tDdyoRhieOs9x+1vFwxS+Al28+5RT>8MubET)nO7@ z$k#bIbRDc>WkXL1wJJ7fWMt%KphR%kp$jOhM4Q_U7B@wF-}>#ws?U}^<>7zTqR07V_%9tNckU$-}gBVItm?&DZ=4{DO z=!g&N`V?eEq->G-;Szz__d47)a_Oq}v$U`TP(QJE>``6=0v)+o1oE-%?X$O;qH2%` zph{Dsk(#m)tp8uPk2&%N+CzT(7WyvOjX&TSfrUmYOg!_c2bUO0rzk@UQ4_~J^GKeenKuoEmp_jO=@?X4=8@)l~T&#cXJ}E ziDbDqZvwL7eG&X<*Y3)7zKe}Y5mXBcQ=tpOh!bp{gxG-diAZNdP@F+xo%xn+>ybV{ zmIv*F$d_44lp*&w?j1p7g;JMbK@I`mlLD(9Kb{mNfKI=Jmmt8G_jf0MXeIH=#AF-v zg3)ckj%H>QCySDx|8ZDuz|mBs4i1DXPV^VRmOL?ieFR(t3^`zkEOOPe}J9x|u|2fY^lf=cGMV;>d=q9@`D@(Fbw?=|_L za>0F_MY-+r4g^1sM6eKP^vytv3STiu2UHp|5=67*(4j+{al0q$`24Sqjx$76Ps)+B z(ewSx+oHziW=$$xF??jOG7z?rfD(~crV^;`J%t|w9f;zH7Dao|r69GqFZC>$=+V5< z>>^zR499d(p5m|}GG=64ynKr7>!D@j9qdfGzDxn?pa!Yh%&Ok6UHWc9EGPvjzX+oA zKM5ete<98`e!RVZex?;}EK`X5?`D)E`d}f2rAIUxiSI8?SEOU`G3ViIyZr13JNbny zgd#-f1Ri?M`h7Lfo%@Lp0;^;{q**T^K7l8UMV!?_o7#zmaXGF6X(|5x5{6{_M! zZf>H{?E<7D8cODG3fr+LS1b=h??sDB_LU-}nTJruLu&^3*lHBJ#1Z=!{J{@F%i!Po zODk4Q7Jp1GM;>4uFr4s=Q2OC0U|{Yt_kI2PH5u!m{D+AK+2;Ve`CSQv>@<0 zLd`>?3;DYyU^OBc44=_^?86BDE->qS5F&u=JvlC^b}0XV>}DWx_fsoz!#?9zk}AML z0_k23y$hgn;DdwBD2c?ZSXtL950ES5j?G@;LwL2YRuARLSxwy2`+-n|1$NJunv*E1 zsmuQJjtwhdMWRufjC z-xY7=mIUGqNd4nQ51mj1aOnnGI1%8KeB{u@a?Vj*i zJ|#yYAZR5Kryw=y%1ihlYE@DW2sWh}!4W02_sknHK1 zOM0(wgDEbRoWx=bv?>Usv95?;FG^QP1wK=G$5#cR z(mpq+_VHBUpHPG*DtA6$KfrN^z zW)!LjSRSq2&%myR^zvQ~Sd91WTiHoVg&hg^x142l7!ad-#I_pv1mnJefd*)(mIW3d zSIG8{8MBU!ZI^caWm@pfn3@ac9z7}0=Xe3GLE$4$GJOc;}K+kWg&CL_xh>!F#}-eup|@& zA+Je|9IPvzkO=Yk@rRg9WsDSv&aZ;TB#|==Z>H*zd?K3*rii`)obC?xuV}P#3--D@ zc-MbU+I23QQ4II!)vKHTu5SO{y|u`-7?!89E;$%sxzmSi8;i|o`OK|FtV9;uht=p8 zY3lb^YdILo(1ag>nU8MpL`aYmIgNmbVkp3q+*n>`#2SoOfJ`aG{d>sBl^#Tio+$1A zSlOippjOiVC#;R!8VVA?#FQoM2Gr2BY^#P@6u%PS2?}_rG~!FK1CnrxI-VLJ99B|2 z*-l7;hQ<1ylQ`MH+}3t)$-)IQewt z9OW%opo9jiB+3A>GYd;U0_}R#LEJ;BI>;cBA0o>N9ph&~OL|mIU-_4T!GH7)(3oJ! z^H}CUkAf+>w_(~u`o$3RE;yJPZ(iO}2*ObG{Ng7RV=qV8r3WqDYL(*;uZWLs8aM>o zFzo86_jmvdm~36xOF#(;CFr2mKLFxP^htAuIFkVYq2ED>06$e@QKDL1(Qo=G>cTx~N|pj;u?a&%j&mZ80^oxU z$PlXt930Khi7V03_9%fM?4R*&5dA^w?`Ji}%nQVWrs^RTh>Bt%9)DN{2Y{#mP-5p- zl`{+E;pQHnYhN-Y&Re|8_ehAwEn6-N>Jm^K4Z8#>h1;=k0UZJj5=Y_;V;O8l|8Qm1 zz#%9ZNV2B88k{=iQ*fQem;#JM!Spjym+p~B8V6vad4X`saJZP z7=;}Z$R310ZM~tq_tQJMeZ`@EXte~@>>eA53Im~DgR!D za~se0?!9|jaHtYoZVg;2#sQ=SZ9;=3jc`i@agS$T#UT-k+@2xE9J1MEea{*4pav*72hKs`_X(1Fj?12`E z|M~Vf6c$qnr`7%dlHAz@+XRi3V}MmUsUuz-oOD;4=D#*sE(V5haL1x z|Mf|^XuwCZ%}^bj(#yz~ZXz76G$q%drt;tYmqG1DIvePgVY|SphSrB%wrW1O9C0C` z^Mbl}fyKb|^uIo{V(9K~RGs|ScpG7>`S(d1AR&QiB*q(06Fl6;e}gjeQA*KPg1}Th zMgRG5@z6WrSWIN!Fh8(+_ikHEFItNY|NAGYshJ^R!6(H@n4o@B4c|t<{PknO`EhYXJI82294M~R*7CQ>$gFuknK;J2x z_L__o^t^#ZGY{^y!xD%-h4@1fl9>Qd#8e6JTc~sxnFT?CP{>h+F`&dT7!fToV!`uz z`u7t%tWs*LwwD0-+K(>H7~#?q_$dQ3J7jE}2I&LA&evZKGoMe#l#gKH+wh;M>yG_` zFdcwAwgB*fMj`YkJ)x-(YW!#5bXBlppf~aZWceUkAn)P6GhGWa5i4{l`Zu<;QHzTK z#7Yp>3MjxjOscJ>Z~Hm5l>eEMpUyasEIGYm9pC?7T7cot zA&)k*%`XMIJio3Y62$0ytZcm?)v?oz7pPA$Jlkz!`=a8?xh(F?vx9FQF7_xLl9_n4 zHm#xI`F&d@xwNdbD7~ZUMzq&9((cvVp{co+fp#qu>$Bnfsi_F{P1_QEKNo#8Y0G{n z@wz$LwZ{9_bLCXmTVu*sNCb^zP|j!E7VFkXe1TN%09RW{O$nlUds~{)L5*`CwDwmp zzC`N;j(=sh4Nz5MJVz$UHUJ2hQ8$meMSVQn>mpaUWV9C-7ui3Zt?WlhDiRs_Fe(b= zJS(M;nD_wCCAcX-@GHDKVL~3j{%PuDp_dWnY8nPl5Fh7Bx@sd-#hZg%|*ex*#pZ&C`?c2Dm?C@Q0+=Z+3eRuDTZ$y$4m7 zuR2HsIUgY=aU+0)2+w$A$Ohn#>cY4&Fwo6>6biKvrDG0RN(Md};V=3xY?hU6d^Cyn zh`I=2Gw)L2rkFOg6cV0;EHDdanBjSh;0C%I zRFv)KkeUMOw_BW_A%qh^q!u6Fs;a67pjdG|6q}spK{6kSXbZ3w1UddI85z&L9xU{m zc?MqNz9fZ0$7P~TRk{jD_5&14Kr&(E?EF+ant$*xO$}T;V7V812~$^{f#Q4vx;mWu zh{eqyGUt{$6?(#<3Av{m1QVMvc`?+b04slBE@y%f*#a3SSg4R!+WXNNRDDdREv!={OJ4QTzV z&gG!F4rZWPL{I?(X>=Og3po`&X#M4P-6gNFzmNzK15U1+(*Y7M0PYRYNbuaRE(w)H)iSuAU|&#_Tj`t zZc+qGY`|o!BdMt)RrVvcZ$xGPX7I&t{;dM9OE4Hkej$#p5E2sNma~g3r>TK7Vl!}} zGMwAE!I9k%mmw%59-gvpy@ppfrS7&@@hdp1W5Tm<_;+(+_MoEy&SHiW77DkTYGRGu z6D;+;k>!1YQm6sI8Ni}Do+p5su<-E3-gadFL~6l~2j>`Wq)kQ1AgjB(8)a37;7p8; zAOB%STaL$VY)GNx36a&Cj4n#V!ieN8^9u{GQ?klADxyPl2#CGKMgC1rr?0TN0mj=$ za3h4Apxnu_1;Kg%N{&3P65xn3LhO`ME0PKX(XwIw8#iiiZ=ye_EDTudQt;P z_fnSa&|N7P=>*z3N=8}Hf*{!LmIlGXn{dK#J zhK9yL){d@T5bXH*Z*JQ(l*~^GMS!^1hDAgu6%tZ|L>nuwEc)fhr)BL97NN1E5J-Y!Uq$QB2F13FtQ^?m42?D*UtI5$oq(DR28&_XlKa$6Fi-S7Gp`uxo+Yh3npILFM`sI~Z0ZP;ZWt@>S%7$&j>6N7;ZwwkO;`;Fu zcrI&baPZzwb-}lShrQH;MD-HW34xuoLl1|M<2r@eG&CE;hDWkUjekkCjR z$Pr{Mdx>XEm>QA>;9?yoZkG2}n^(qeN|d&`M2bL>VUyqjn!w2m&JffPa{;1NP*rV9 z8$hxMkWU{@FVUoEk0>RfaRU&6FLIg7jleOAsQ)VwGh@n?3pBmHEVL_}m_w231cGxDwk> z@lyOv9mNy;(Cqs^mp~3hpirW8#mQQj^_PODPTo!wpE%Pt3zj}l%EsX@FW`l!j(`<7 zP|4|nCve}Hm7((_D!7RU76kVlFXt3oe(fc}FsX`JT$r2ajxz(wRK1NS0`O1)>{OH& zttX8w7T%XfplZb)ryHUJ*Q&F6P!J)wR8fsxIw<_j?j@AFq>SXpYfoT({g0>uW$N1_ zM4%I?!{Mf)=rtc(TWd%N1%ht_SV8OSCkS}+&C&z~)yW8h3zj|ofpyqnnwHkKzwtq$ zqWi<4lBEEGh+)W0n-^LevMpgO5J$8^P{?PuRzR3e#2xtF*`JrUkApNExlK*08E=Db zkE9d!E#>c?EWd*&+h8CL?uxwVMc`6E?sUdxd@HGu#jE-hYzc$~zBM&)F&|)T z>s=#76gZI@Po$3%2?ZCfT=~LgpnQi&dl5xIfs{$rDN5!r&{8B2v!7HW!ovFA&UBL;i-PVc$&#&>#VhS<)Mf+=i+Juz0SoSgSD{fR;cpC`~*JOlX+ z5owY}<HcJQ0 zdlA46%A3(VC%F`NWklx3u|B>+M||+e5qaC@wcOkfiNOx$%G8hCU^Ox9nLq#=z>T6+ zS^v0(Es=j9>yC)CKXZl%=;tPKQAQ#C;w%^zxYS&1Zq!m&5Bg7Eda`uIqASP}fIAmi zkpLUc6xdY6OIecon&|IKP_!YQtGzFvuB+5(rD2OE&tUMzemEY9;@sg755u8$rXO0) zKi^&itr~O0v&lXEukX^r)IfsGEw0$}u1J=M=%BZFZm3IBXp@kT2D;MLr|ZPfbx(1? z|J)3gS%{}bW(pWquB<0!-6-7B$ajq9l+r|p@uk}sV&_vQ)pnSHDM)4B5V8$*`P+-9 z@1jOYV&$%O6$M|A|H#KSG3Bv4F%<2F62#Q2bA@AnE&~Gtp&}X)IwLHmnrkJ!6mb3g z@^-!IvZ}@h4uJVkG9I*c7kE4oIS>#|o~!LIj&AiCc|%VOI8yz# zOdE^p#@{wd)9ypAM>9EC+xWnEf^-A{ACN)qm~V}JWe>JjeVzw#@}X+mal5$I4Xcfu z)~sE77d2gdQ2U4bu0@Wf<{Oy7plk+_4q)rIZ0XG-V`B|i&&2i3MLocY%(dyxh*mpO z2~Q$y$I-$3!BYrH7xNH$tclF-fYVwsc zJ*iXQCGM(;;rxSX?%LJI=s)D0>mo0ibMRbDbxouH2Kzv9CRT>Oals)W6D_Vae?xNx zVBFO^DiMNB=Lk5Zumu^ASH$(9z|HPFrc5tBH*?^K+Ey%WBzkUrPLPa>!w02okqc6$ zSy*wMh%45BW~)&+TDk1Rj{w=SRG<=W>OHilrKcajwf6X)qW|HKBr2~-KQ8o5Ip3QQ7`P>h zY0*h!7^u#qLywrE_>er1TLH6YxR0?UDxAAZPAGJx{_tR+`ojnEv^SaWaipW7S{`k5 zcLzYOaJC2+0cMJ3#h=@V;0Rs}^WJlIU30KbaP3R-c9KPYrUHkp<(}7>(W;dT(>nZi zO5!3SyWupMyu+!jWq4;CX6ZO)VW8UVFvz@h+}!;m9w+l%wC1LUJwK`*K61pkj#hJg z4~qB5uDr7B?Yr^R#lF;JX|IrXr_Om#?QwdA6ASDuq1*J2wWCLe7mpRF%+OmH_9C=E z(@&TKoDiF9B&s|=Qcft727Xf&{8P4=nXG=|SOCnzkW=3UOBgP%3Bi)68q<$fnT&7q z8>-Y@PBoB-)2K|~RPHvagb zXl_hB-;%#({rbreS78N(Z)XO~fOF_4D_Gc(Uh1S5LgtVs>Q1nOx=-{U!n*-&mT!CV z5uqLket1Pi;!H}O4I(;BOsb5`>T{F3-hw@VY4iYyXQaQ7b0(c|%Vc6;F!b`uL%=JG zV-n%w`!i!oDBvP>kh5I^OM7>{Wo(K^HEL#74JstSreZ&P?VU9=Fu*gufL#sN2}ke& z+EKg@5GpFXtawXYG%=-fZH0r>FHn(C04PTNrUAl=qIQ7L-I)P0zbbhauzeFO5MJ^L zre^pMB0;WETWT3m1a{o{BD!Tt1d~+67 zQ&w&{W00(b0$aFD0)taH%P)N-mB%7I zSqOYuizP@A2&u1w;t1*exqV$utp)DH*^PO-8luk3lQQ>)5$8dN34FuxZ^u)$rZ7S@ zY};17si_|v2B}#C6SS6jZ3qEKuwU-9GC{QkG2%m}Ft?!6Y7P|22&)c@GDX@a3t9~l zZz7In*&1K=cAOsvmYjay24_HE#CIH_`njacKWY_#6|mcbu0M=LBWiHVLGeN)4s=i! zAay;wz9WKCnfVoyvFD?My?p~&`C#GpAIUbIh!^vR=!6t+5+0F{@9b=II*|}9CD?XqeNE6wi8kkFPNhW#DZwv)laCX9v(!Q7H&hP*VprOzbb0@GkT@U(ew7KhCQ zR%}0FQU1Tqn%5CU6Jc@){c2*9A0w(K-5SmbxCk95Z1V=6;vn0V*1H3{t9$JhCW&I9 zaX~67Dn#ybtcJV_5N{Po2tzGC8yMgmac7YE5_@>!K zlZn78m0w99&l|_e-Lz#(m0LWJc{y2mwC%YH)s=aF?%eF`cxQw_e{|q{+MclJ6FfS& z58`;)cYZH65qC7x;XdvGnN&tk9-dMI`FaAZ@%uW;%F6Z0i@UjyGe%A z5KVr|R7fM7b)Fzb^wsjmc<&ML8#({LJv1zg%clx5ozt6>n+H7zp-hslO9go@-It6r z4s$(rB^J!Hxq)-?P#OF9nE*N?u|FJk<@^`qN7>sQObE<THS2{xTgcEux#?@% zUV*1CrI?{%U6qBp4$@KSA$Y%R@o3>BmI7Stn$f2CM)zx zDlHwio;43lPzkPvyib%9F}7#C&C227Y4o=cYvFsZrC=@C{u; zMLkn_NfV+`Se(^Z7Sp>l!cy(=qa)eerfqf45GNr$kMC@Ue1Qly3!h0K{I|0kGPd!{ z9I)5iwM!29L3x$HPM5cxPVy>RD5!y?`K;FrWGBEsS)^GRidr!xAx^UNnt=|+d*bO^ zG5uu8iN@Nx@S6z~=%Jko=Hiu5`asryXLkfMPX=0KS(b7aeV(4IYvn1n*52(VdppVd zs0-{c0ZPBKAGn*F+thgfJ%UbGTgpnA&O+c8WI|z|MlUPL7Wc*vxAP*AIEygB$y!YdoN7HJiA^rxM@cT=*C8WV}FL?c*S^w5)!JgEcBTzPV1SAB8 zO-69S!uoSA>IE9cUVE42Tm1g`T)2Cnr^m+Y#j&JnYda;Cci5_!493_%(9}|-te+U8 zuy*`H--S;o3y_>>m2^5y_k=GdC1r43JNr^B2msPit7{FdW{W8b$vdt5tpXC!XREw@ zt@iHSqd0HOgmGnL?KDLGX2!qT>4J{~nYOdnoCrQ#zl!`6>t z%bDF=5JQ(UZ-Y=fpr*mW{e%#LX`^d;h zK!mbPPk1hKf7e5Q_g`M}KJ7qxMhmF29Wz0GK>kP*U?$2sX@(kwrm0_fpe5dneCSiY zO*wycRo_|EWqA4LrVhV$?hLM~`u0hy=}+OsTi6rZMy7VstYLr-MA@TQLpXAWG%%Xk z))6^ZN6rMdR^x>4O^f`)z%j!!H%YtlO~?Yz3Lglen=Xw#f-ls$Dn&Hasg zJyzb%ptCLiGxtew4r=3L6pVxhP=sirkidyf3sULnFHpag&)KmQjY zd?r~nHMMrd+uL~Si#_HsPgZi52AO5T9^u4bMBU)usi{o9u8o77!WBWe{PLJo_n__C zRRz#^?%+=Fw#;5!yQ>PP$j8sto?IEQot2d209e!;iu(mrJ@T++KC zP-c;Ps*;c(mNMkwI^_nMZ6y;E?^Si%-8in{*g-bn&8tR?kOhLx8oT7HjY$PzCzHu4 zkjf9SF~>QjUh^HlutpdpUyp~0TWc0y!`H7FXn;ed5{2!6Sd&PImr>^JBN68wpAzdXh(BU+TPf`^r`02e9r9a*;0`PqoEc`b}Pfq)F4&~zmhsGx55`@^VI#bsp= z66CC@MIK-+({^9vka_cGqZ3AnbX_}=v-3-ZC8Bard8l@CQha1OR5+$@JmmxE@iySn zMD7)1*Y@!L?Y~xlkX8;zLU|R(x^?HS?yN%!z@*mgU}xuY-@@3$6Fja%&k30UOCeG7XiLA4}O3O?$3BggB9$L>h~gM0kmzt-#up>8!i zdD6i)A3zdzr1&30Kp`c>X*HQ>pUbCWz)7cqk;-RWN*<4qJXqNA(Q5YO!(URCoG2t* zQE2pULU+pa^tU6!%mS(>SF4P(uA`s63cYbFiYvq8)R2KS>m4HQII!C*uR4)+m~h7u z&BdsfGIo+e)1$*rPWIiX=z=_6&%dk|#qKD*-BmR?F_BOp6RtKK80KYRxE=-0zK9>SAZz}RY7wFJQ>pEpuRD* z$2xoGlT(wO)+h{o9L9&%UN^V^OR?Dm*^j6`f>v8kMJT3;WdBjjYvbw&h#i zxinHZphazpYA^!=B9ksR4XtlmI$5vM;2=l z;24t6kmJM9w8+X@y_+I7NTemj8Lxs(tPFJqIA%z#N#Er@SW1n55RT?t^eE#K0W*b= zAS2@LtM3jF4JpvaF@jJa#?upss1jF(T#rpkdW6h1B5nYBc76S*zVO<1G~%_zSaVCC zW>~k%>l(5HQbPd%%TPTie^We^fsf!g^mW_R81lbx{)eqU^!Ebv#XzJZ%gc0ZM+nHY zI>2QY_KjPCi{7w8@^zR-3ul7qllv}bt81_Q@xxBh*3-jdGd9)n08$$O%u!lSOqPzG zt-&{*NQA+RWNZ({10Y5Dq}evqchSAlT)=7p;S-B%l$E+wDn`Rz2lWmtTWP?}yhJS( znQ|*xSauW@N!;rQxVi06OW`l(fo39Su29xboKOP0N)8{1jnKVZM_AwkHEfS<)eZ!e$Rb#(m)=w3r8zgNAU=+_R$c0 zYe0@-K-Fo`24|j(CrA&B-AL0US)&C@)CIfG0c350QQPNf&PcQL(Fp!w779o32p-!1h;81AQ`iOnS0<1&ib4{ z2uom8g39BR0dDfC+O?d=$pLa0{<`=wPp5)e*J^Hn%AM_;*bOT9dqAvk?{rB=r5TZU z#6}!yKY~_KP{HN7bHO>0NOtfk=k_TH{Zo(;3m$~UNWil2(8x+bkhEb z7P3~-4^J<93-$&OG=Or9p=*Nrj*vnSh&(W>YWngeAs~i{`c6|bg!u&dK!~21B_kyC zrrVV@pZHlb^$zb8e(aTo^TZ#@;f$u|$Xehp_w7ticxq}Y?)X6j<(44QI-&|zAE&U1 z>N?Myt|gm8qEmIs1K1S-1sS_=wl&8x!uoS^U*iZNNWp?Zwca`p-2M`&fl?}bLRyIs zDyQL94Gcw)YjLXu6dLfwKv9=L7nA>m!_1Eqpb{>?TSHi|v~vJ05tgZ1Ck7Qm6rwbH z9;4ztTL`Hq&^wqwfS?gKr07qP?DLZt9T7Kzw`%p6gZAn%@y;z^SD)T-fzW_*KCpgovd1sGXyu$9E?`>{Z(}kB=Se@LQZnPjG*_8Z?rRkpU5BMQ9vVT;@Cdw8x`Z?Vfyo|G;UJ< zsQTjNpXK6w{QjeTcG2%qvE+KsT`o?jYJ=ehyK+!~J*wT&%10?h*}HzrWF`dtaK9|@ znRwXj*bc*a3%h
`VAMe+?=o4>X_3#$X3Y;Z)<+=$SD5gaw?+N0$Ec2j8r!AzmG zUu`SjgA8^vCMpiGgOs3Dcf@i<07^~e*P#|Ji&QazK+5Z$MA6!^i+kXrGJWS%iTH!J3X&pjG zE@Xfv)hk(A7;g0t`JIs=S_E%N996XRX)QgSy8)9fF0?P1ppgdiji2}86X9WT3Q}M8_);JSwF?A?a#R}l(`ZW8i>aR z@Gg0T0v;kT0n}qAgaHKB=sy~K=?wwIa5&|g&=4nJf?N?3L*jn_?Wx7V^&M%*Q%P+E zkkSv1xpOC#gfQ&b0P7Ov?1_>p_eU`bGjXw`l62WNNLaY2Sf4;oz*kYkT632EJFGws z;;CZGcmSrw4(QU!y$qqwo){G(^MrByJ#^|k1BwnYdb)YXTB6p1j}TPl5azWMoJT=b zHfrPW@C}HOGf_4KQ6w$~^#@MMVORq&W+SZ}!RnKe4uIOIhIceR zg1DaGj*gD)5LC5V&m|wC$Dshte;^d#X_Y2BM~f^nhqIVK>@WY@SiP^pn)@1Q;_%TJR{q&1xi06Xutqr1-KX% zTY1=^T9$Zu62UKmQlia(l@;MZa8l9x&*3A_Afe;TO>_kMi0Z_E)*)2%?oo;c+FZN~iyodczO1)qX+!k?JcrOOlIK~*= zSz7Kn?F4U0{1$kQPeKdIuTpPmU{F&%&~Rmm$z$p@BBjluqVGGqK~A{+`fyF7b+V(Q zBWW;%r>TsmXcH>6@mM79H*>JFk8?El=sP`xyGekv@(y|VxwkZoGJ{o!kwGTab%?N1 z580yxkrZFuu|o5jB1dso%8(6+n%Qcn0888N*fRoa!}I7VOv)K4Bp?3oBuf8{dg=d- zKLu@Hb(?`w@#57hLez!d9PIDEOQFgmwW^&12Yr2&R=~O7trJ2ek4wwBz29m`PH{{B z|I*X_FS5S>RsL4Y#&AL$l>rd8@7%Ut$32#Y{ChfC@pAg{%73?{zs+e`(N!w{7iwYr z_<=hoe=6PcWzD~TM9>KRyYJGe#^WM(=l19f#-hjuZ!Vl1;4)ZPNv_oWx@l$$`DJNWQGiO<#CBHGDTC`Q zh92a19XTu~Ydq8{YaB_007i)^#!a{WXyx)HDDQij{u(|8+uMg$2lO-Fd9pq4@Btnx zM)F4fG`;#CsVhU&co?!H$~Ndk?|WvPvHXdXf3EWv-ReHQnbmZ4*a`O}qch~!6vu9X zY@57Pt8?b}mPGpeE7y}>wtStNy{K`TiM|Ye#;?;WHZG{u`J>a?IY$=V*^b+FOEJLRz2>J2~9iR)%_#e=4rQ@d`(A< zREyR4VVp)6n>>w;9b(zl`N%^HGM?DyW6-X*#i%E8o#HmufbE?6*T$E0DsLArf54_! z`)1FQ$0Bp2e_VaK$UM)m{?YaIMxNxa<{yM~ve6F3`t_-9iB+NPtHNVMvSMBwuJ=or zcU&Io!g##{QN>AhLR;kJr(SFc{M3DZeaS_g&TRpbrQF1(l{_bu_V$mTEh^TYO1Tx@lY+3jbL;Sis4`RpPXj zSIP-SuM=Nxs7@7$eZR?m>?T|GxvfqYIlk*B)9!Vk&lb`DCE_J~kt^6?)2p?|)?QBz zs~4rR{?HT_ex0$le#f@j^Fp=t8L_X}>jT)2n;*ZOuxVGqomEzxKLYOY{phq$uwHzv z-1q%hZ{+o*Tdp-bA?2EyyLHddtHg4q@=K#<^Fw=6Gw<>rk3#?kYYu`S| zR~=aFvBD_$!en&T==E7%6a8`f>!V+SY6R`*{pnw@kLU2-73sZm@~)p@^r}~KyPdWR zO0O@cJIXX2q@D=q9NJs25rC)+w;~(Rs0YaZXE*h>tLL=yWKR zHk7)St`3R|5}?VZa-ujhi=TYU+d#zDebui6|rc{BI){#neMawE>TIH3>RE4yKRP$?&8eU$c z{}D7%`lYlc=&s^4O@9#G?G;CvAFn9DFGbC_JZ0uYqZG|j*%6HnkrB2I&r&mr|E6m^ z;w$XVukToUn=g-=fua<|aFzNAJquMXWzTs7nkkAIbum4@fO?+Si)Wg~dA+m5EZ@v3n)?bm@HEmrrakIR%~u+pAS!d=r;H4^5Nq>QPuJzG<)jWjzs8*X0%eo=_NURqW~Ede zKG)Amt6gSyzhU`lT?wmS&QFfGDwQjnlBC}?1y{V%*s;;MzIUEM+k1SvFOU5e z?KhsMW3XRW@=|$AJ6*B%JI}09<5Ta`y-c0Le%jyAd+<)JC-X*)^cM+7V~fAWcjl+r zYtBAoFFE>sd(OA*Mw6GnC_8UTqT63|r83%}Iy!8#e#xch`~J2BzWmA7?egh(Y-;PJ zp2aEgTX9!5FVc;idnZ68U_39iDv)|U@~6Sgsl*H-z(*qN4lKf_?gQGfsoc`u$E_R(#$zq+=`n7&^!?;`2(Oq9I z`Shv1{gEH5Dr9@-=@w%Ts}Z-OhG&jMO}2@A4c}^Z-bJ3F|Bhww&3aGTZN}_2SB~y^ z)OR`fcf;7J`O|Zo>w-%-8nr7{RNqmewQ|e6?d_I(n}1gJW6^J!VD9l_8m@hzw;%QG z4>r|oXB{~3zDHQ8RpS01CxO|qLqF{g^gmjcW%S~3ouXFU<^tV1pS>d6GKK97rju`9 z?i<4mt8OeYtEHQLc>C-n#a>1&gUkM>6GoaS7t*GEZHX6JtSmz{cMX8s#_nvuSs1(`Z^*WY)K^nWf}mdv^cSquGUrDJKK6 zueWFZGBX?x*chl@%Ux$$VwWlKck%h%Y=$4&*^C82ZR`WPCY@xyw$iUK+3mT>C;E2e zqK2WKkxAXY**zNmmkw__zI*k`vJP@ z@Y3S3zDIAlKixVMSl+|RlB)c&?@;QVl9jWXy=rwErXJ1As`fs*z2tVerQ-L%p4(30 zi?`P2XID2x+%}_GpxNeTY0&8>XvW)7e1hY#YGUCI4cf9&+n zb}?QlJYoMd!2WRQz7y&p+%kFhKE19klo*?_ZWA5jmvNf%XnLV>m!tOf6Rr>jTi%Mf z>40#Vx2)UV@$vrsJE8dV4IjVBiry7J`NbzPxviG?hDOaJUajiO6%5(=PI>&Lw6tPRch$5-6n#g;akrkyWQBpYnyvBJ{lhFI$Qr?VyZ7qu#no{Qp(ZC49y z6CbuWP2+a=2{gO!X>=-ITeT=L-}dwcqcWTFOIK!G4DT9lp|#mlZ20Kjx4jaFCe}%s zWQ}|BbfgiZYvvq^# zz0uBzUpBJ^UpH9(6!?80CQ|54isebKvn?4}I&J=4s@g>_49lGbB4=(|rXEZG{^n(n zt3{LR0l7!J0}pndyfDM`w&U}3+tt4&f__P(Z&rPXkPs~CryhN@U2wIjdhq~nKJSu> zo^r+ThJf*5YG;;YACK_{$Cgtq@$wVH-y3^H5`Xc<%$etXTvt|q*Dc9k$Hdzh6Gl(O`q6&< zo%}N~ddJ6^^Ffm^yNO~?DM z6%QS;dVlQN$h#)$n!uckZ~3?ua{Opt`l>YjJ#zByiz^PN9Ez=@jG839eV#3hn79s= z9X>KP^IddjfaCsFwM5|vnSjy3)Ai4G&;k=FcS|{>q_LcO9bURL8^RFH->5rT1KIK*P zIWBtg_0f&?>C~cw@5TzuuG~|lN&S-V)I z@4mOmQjNNNV^uq2U+$fqeqO)#(8Z4UA2fNxn@UdR9%~Mcbo{NX=vs6yHYz)pL8|&Z zgI+8B@7{+O1{_2TvXbV%%1PchMl;Xb=|7s|@coH+&W^bF%mbbkye3~<@?SAaWvlh% zKC$4c*mYCk=Y=|}I)C@5Czn3?c)c!hKd;)EYBT@))}alP8;gH<(Js->Y>tndr!{!= zBt1L$mhchB`tsBT-p_KM4}GgvtR0p(@$z}(lkzBg;kYfGCum?78&{G5iAku3R^? zS8P<-KkeP|$4&Lz*8$zx%Dz~ILkmB5zj^GsdFjcG8Wp!4zx&Wa_IK#^h%sp~M=|{d z*M(?l{?W~2{b%&rcn6K843w-3s`$qquUo@W!24o$r-3M4Ld{0wcGaf2q71()4N04X zPgM2{4BXuDwLNisYk1qevEnaU2{){{tY?o+?B($3ak+GDYoKF-{`1J2o5s4YxK^GX zaJYT#d7+KF%g)Vwg-cJ$l7BDc9-e5IudzPSpq^r5SuB^=osSNJn>x4aZI^l9U*dL7 zE&9`61R>ysFdgJiBk^}CVzF{f9 z_J=v?sc1-Vw0W5P-9y_Y(59a+SMSTQQ)l8PW{i!c)_$z7BEDmDP zTFzf;OZTenED#ebf6!>I%r5FX>?Xo}{EltX-7V`(?)BQaOgi!NJ?0x=iJV-`#v{o5 z#+D|TZm$3X6KnI{AMdH^dDkn)!wGCZra$`5z8?e#Jn z;JohfQ0YjXDp#srBV924&*yzvZ%#Xle$n5^A!(l(9%*eRBD+pM*TW#4`r5(7q))E( z3hgh%;#W=$8>m-C#KiTptYGVNewK3cb8b9>ed-4UH zWsaBPhs-1PfezB#23n_#i;O3@%nFkEj$ia=q!!1T7Sz98;Ex4s5%@oF;M1brnmG{epc4jXYQil*Xp3KgYn3U z!&f4=w{Pf=uKs-0=9anRrbELU9@#FPR(NA+Czh>MXm!fdOIqc~j%5A2Jzl9baTA|T z<&Q`uSq2E+V5vE6m!!AnZdU8Z(<2mtBHdoiPaCa!xiplrlEwNM-o_Yb{oSo_^TO_~ zzOUaq+T0`yGTmSJ>b`p|(GZxRNfWR8M%HPvV}&f=Qna0+(cFsGg>^Ge`;T2nV6J!k1p?~ zsyDx*(rm&$zDQvD{88wTgMPHN)%T$oX;0Ck31+ftUYjI1TYogE)T`y)%MR=@pZZ-l zMDgBww|c>HVb?+1YYyLAUf=N@n_b*lmbI{p=EN+WPoMSfbxt zaF)M&6MkBKgi87c4Ig(V#B3|Kp-+5k{$9rsg>5Sdd zy5C>(i=5~E+!aI0y4KZo9K1AcF237)@9A?->v}(5v~_lgK0T$kr{1FSUAL{xR)r8> zo;>HRp)MaqwoY3}a~bdoh74Q%O1x^*dsI@9Cu2p-JWKAnOqF4$%5}$d&7O6xWL*^_ z#g+Q)3RC+}ahn5e*&i6Kx3ioH2ot2a!gyVV{e9vE+O%r}DU5UH{cOrZx(C$a2FJ9lc0 z^ajo|^&2>87A5b5H}PNFc0+b|e(3?E()KsvR$*-D7t74&BwAGS+I*9{&C}{ zs~rEpyU9>1TaoF47h-R@)F)4SaZC;Chi9_dDx8TrviU;RX9s38KF-g7X3v#oey5h7 zHl6Vkw&rfiGN79gX6+8iRXuf8#wy`ti_4Z*%;UV>K|OH+(g#k_cCS0{BH21Ea;N2m z&jvwZ6+VsC8C@>hH_SQc%6@!x#DQ~Xu)}vPk2mS}ll^169U4_@18%-#-w|Wr8{b;y z(sIyVT4l#)zsvrS3!LBe6pP-hPrmCjDd}=U(LXH5zS4GG_d(fglgtL=txhGM&Fgm- zhwNYwUdehr>$-p(zjbuY*vpuKit1Sx@6Yc{soL}B)~BexIjQ6}DeLNSJ?7E+k@O(3 zRo(|a#kky3@VYyeuDK+nRDCNXBI>z=MSyE)U=7u_P90%`!z1ZY{>q=4SK)?aE^L6%#lgY93QD?S4tx%W}4bgSpBbQ>oB2e>2q4AAEHRI78o%x!L zK1J8&HasfSoa0DrOK&c&sXS`2c*K3~`D3Ztx;GBf-(LE%9R4E}=_IId_)or*b;+$M zX?xr6Dz>@L@6Pw$THveG3tx0UoUi(ki7({Msg#r?g>04gNAEs2=4rOE+_CMhQozT= zVI^DFZ{I~#dc42Zo=f;`m)pJjPt+WX#zTt@{+#vubxxEn#@yK2P`gXJ@A>2D-%L}T zOrEmkDV5IcpPfr;M>|jD6s12*FG$Zwf0h2^^aJ)Y8?S8Cdq%A$pS^7`xM=^F^F1TK zV>ww~_Z8$HCA_i=zq96;?>YHryu$Ci55yWjHaVF$;a9fhx#r=PV-EL!KIA@;qk2Rz zYrS=-koKz(Av`t$8TZ(Lc?ptP5_MIZNGIUm;t zpW9Acs;}Z~ea&QIJ$!yL$Eq-c zpJA41C4;eCdXLJ*MfIt@?eiu(#y$>nq&ku8>#sQ9Uti+!Tc{&>>Sv_~Gk*T=e-Y8ZuthmWrJi3}4-mXmFMdhp&x$*q$0W~J&a(DtDC0Xtt({Ujl?m6Lcdv`M`+)gVScR_r@jlvjOi!;gKl)Bl z;%M1v>ow#qeAAyY@9jzJsLn7PtzLEJvx7*oUc@%`}I0}VTsq%fbcS_az3!KU`n%}xHLLCpI&y|v z91nlPRs1L0sbO3+E2lLj`JHQ9VMV4$gw@8U+^2*#)!6JS$@ElmJ#TT*@=LMb)>yT} z{Hyf4N?M~zUd{Fguid);OW01mwul55kuz%)_vB=m9jRh|7}#P9d$M@^`w3l`?XDH67-&ozNOwFS@|^a-HI>bKfSX*d|bzI_v80kR-w~z*BK@2 zXd_kroRq!1^ft#VPv(BZ)j5x~gWhNR?;TE#O5VmYwYu6f>Ik*P_YlpyTQ*1@>G?E} zT}2V$dX!6F{6fBj2ep-9rKjNgL3fS)*O|IY?>u2yJJ7d6SGd&kegB*0_5jZ4 zTT+{a-|$>~cjf&9Rmt!%Ej`h`&ka9S{l=vVYf{}T77iNC?$`2sCn>${{T6Zk=&q;h zhIXjf?ci1z4e_NR57I0~J>fDQWWj&?APE!pzdpzV#u_rVr>rfy8tukx=RQ|``26Db z#lA-xYz=!vwYC4ZIp;C^nT6%rrKxF#u`%bhC>>+vY?R&9zRbTDWcg;Dw zX!rHHDEYhTJ0HHiw(aQlGBX=be*a$|9Ug6AkWaoj|K+9_|Fqa!88$!t&E~fp-WjWJ zZK?kEW_?;<&7WD1ui4&zv~TAcL+;Y&T|JeXo=xOFyzH{inI4{=4962ZCD(J#RbI_| z{?4W79+&@)^o&&Pdj)TwllxhnsRofpL)UH zsI7;^Kbxw|Z@Xq2RT}E_GHuBpsqmN5?DM{tSD3qfmoT$4%&6h;;b;4n!fs7myaUCV9elXA84$+k!95y7Az5`Tx1T z{+G9}GmR3JEXXwcZUS*FK3=<-q4?)UufoyjD$ z#l7k8p7THF{LlaV-~W5>G?6@1y=2)6S^wVUm%p&=y8n6S&G%k@&d&YEl0RQ_@cpY6 z{rQS>M8-tq(5~fCh`nxIBJyiEm9GFXzeo@C73eJJ0~I1U=+R1%T4*GUZJWr;(?tBU zu>rF|49o=`U?ErmR)b!!5nKwc1P8#|!QX*fz-{28;9hV)_&oR$_$qi9d=oqho&etk z&ww9*=fR8Mm*BVH58zMWFJR^zk#oR>UcR8EgZ?U>v*)+zF0@?}49#KY>t8WDeL4(%@_0Rj|B87Sf3Os61aAR91vBU356lIf zU@=$$&IfD2Mz9%d1DAp!a0N(!{orljKJX*(JMb6an;@^2 z2iJh3;3jY@_z1WQd=`8gJOh3Reg<9!e*h;zXg+0tg`fv)1$#gi90oUoW8mZ9)8Iky zB=|S*Gw@p=9U|3WCTIaGKrh$^E(LLr1qZ-ka0J`{-UB`WJ_bGoz5pHt&w%H_i{SS_ zI_XQ$1Uf($SOU%mYrutI0PFylfjHO)(jX760oQ?B!3V)VfP2B`z*oRGz|-It;AQX{ z2rm$61fAequoi3v7lX^dFi3+OxE9<9-U*I@dO~glbfeJ3;x&<0Lr}{?&;=HO#h@Fo zJP6B%ECtKJa-i$Px!_G;B{(1Gnz0J31{Z)ggEe3+SPwRWi$EXP1U7?yFaWlItza9t z7;FbSz#!NOQXmfwfP>%=I1H`d3-xO%Z3Cz zIZJ@$yO1-zEx!t$f5P%-FXfAiXw2g;LddkU@@?=%`K9noQ_=XYfajm>2Z$|K`$Xem zX|i&SM{P7#y<$N5{RoxUxV2ttqj~hw_?1^bF^^Z97LV7utG(7uFSS=*?UmQzti0Oj zc+e{bbX=$(<#l{0ujS}C(Kyw=^6H=E%kpFJ+Gje3^tuu#ul}#{c+H#k_-o;_9)B}@ z#^aBb@pr z)iLx1pkwSAp!4`qk3J36IepZlpMx&ouiB#_OPAWQxsZ}|>@MVQ*rOvJO?Wg3?ec1; z{re@Gj>^N9cFJQ=T_<)~I>*N25OD=*2fxokD~VLoRh~RVjvtW@6PL=v)ac(W?UMhn zbgulw(#7&qXq}fY%8K*1q@(2cC3HIJ_dsW`GO3>#Qe)*aX=zP2difg3@t>q;u~NOy z(t2yxah={n?1p50m0_Xg6lz5H{?cP;5T5|Lw;&XR9h+T>C88q#MI&u1*Hl_#Oi zUj3S>!Qb0-KyI_NLOx)rk=re;k~=Jo$VV*YEM%!)K4xj9+-d0w`K+bq%2%N=FTR)r z<^4A8ws(y7{4wbkPv7d%HjlP@bgoC|d33%{qQME&yycQ7Z6v_ zQn#NM&=cDK3)ppj1zqUr7kcAhAw8k`h3rVG@AC9rUL0M_GcCW19@g@^C{N4R@vZe# z`Q4se>#6cjcvRz4dyTJ)cGh}#F}qG!dY=4?M>Xy)cFX52ohC0q7kTZwh>{9gq4v+ARNM)Uz{YkIC0qsrr^A^2U(o^-z(buDYA3k)wnyO!qz6Je9(Ca!j zRX>P+5&FB(&pm}cfqo_WPobZ83Vi|nM)b$g&p(C!M)W(;>!tl`{1f%Ng7h);dpv!I zr&l|@E_aC>_w=2lwf&0vJ)Zs`D@Df8_W1x%J|#M_>aSD8TWbgVW^Mv z`vC20WAo@DkFNFTB_2(C^li{8qSQQh&@dN4qvuBFM(d;gv51fLp^eAWCbL@xjQE?( zkWychd5hA((3m69ZEeiowsWv@rpbU~{A%f@Yl>-~o31UU18zD}Ob4UAZANRlCF2!B{NtlE$i!y z&z8-zDZbR_V8pTY)4I7m!?PDUri9hC@Wk)Ni;Tf)>%1gF+XO5hLN=++vH7fgudj2_ zceCdsN==Jx-Cic6#{4nvk!cKL>YRSj(zNWQ$Qk~UjTu=d(;WuLkxXm}>&y%%2)7t6 z%&HfXR?|#-w6HH^Vt!(*v7XiUMJ3-_>k0Y5Y2@2aBfsP{^0%Bu9zTtI@9X4l|6hf? zh6rb~x@02L;Hug6f)b5f$umz4R zwAI+m_w-Tpm!W5*#_I8--Y44))z83Yr?nZ1%*11{AFro8oeA3`)9pK;vh1Kbpb9WEoeSmevt*zve#heXy+w8OWM ztM@3jKI@Hj6Peao%P7|4`;%m<<()@aUO(Q||MSR7 z5ytfVQkj1|h5wUf{)_GAXQL{{Ta;CmWZLd-Y&9iWT}f77Ces+T{~M9DLRrI|R!(J2 zCd8VwSt3q~_H!lGuEdvORz_oOtPjJiSFGI5FxI-pr(_zfrR}FaoAGJeU`Y*r+_u)3 z=ONeiayI2$9jm4OVbg3DNF5=oy^gOgY;0fphVj{A+M-M4>Wdp?$6Au}cjbb|4n=6g8cw>-ndtYj3Hp3(M-da8g}2mesY!)^%B_uG){Fx(m?F9k?8w`p-7`0r#i~Cjdx+M<95O#7t?2@!Inl*PWQ;7?|s;6n@-reV@1my zJ%z3~-}0VL=UYmQQ%!_L-CHN=T8Ounesy=P8_-S6fqkVpp!(6b@63U-oXH94w7&xJx}Y|T3P(l4T+%#sV_pp#5giBF%* zM0zzkWFdT2ht3OeItdj$cYMF(p{lv6LsnKz(ms-j^f0T#!A#_Q8*zQOT2?#}DaGKX zE2)vI@0slV?xK8UC|b(n)>Oyq3uSfexFr{vO})ZCZCf9at_&?J=HZm)`d|LJHMGu~ zc?0FgH^6RxJ=}KJy z%C6~C(y=M&t|{sBrli+QNnbQ2ed(067Oith*A~6>*=IjCN$4TyUg%NiDD+ln26{6z z3%wmW1|5T{551J?TBmcoNMY@Mp|l%L&-(6a;HET>efG0@*N2|3)W>wZs9xjJ`K&(m za`Tt-QO*Uktc{)!)K2X+hx%4u`o=?jsa&c0P^xuTs(YEzdZ7E8mRWojRC)RHr~1)Ye`d@@%^Wi$EpseF7molJ=75Qh&GzK%W$IF7xPe zkFJo=hAle>+IRK#@7%CMOrJOeZ; zDTZDW^vJR)Cae0hxqaQ)v1Dc}mChEr$KwYI@$^;QJ9~F|@v;Heh^Ltt9cRo-w|Uunq~-LM z+uP%X0*%soCX`Gjlz)PwXr`^2XLX#}e^EQum?PchKv6_sG=Vex1oc zJQLrilW*EU@1=YCw(J<}-NI%leyxPGzrk=?taDkSZcV&_w5<`3~XJ$Vb4JCmYu!*5-AgH*|2NF zcBwCuY~8Z%qTVeVH%t<4+pxWF>-xTRa=qD^$tCmI^nqj|Hj*7>(XhKfY%G^$z>c0D ztFG!B9ZRQ1QiWK4d@Py6D#H*PA7Ql( z!k)7Z6(j_6fU~F`A;ix_jY}wzWGzm`)2VBcGLu9qmrRtl@*SKk#`98HTm~hW9J85& z?A!5lUcwBTgi6*P?jv%}QBujxoHMnIFle?4EA(Y)o>VNsU;qTCzO^%CsWqI@ds~!VARmHcJ(nK4wMVdYflr zYFp2!a5;NUsY~T;=j}+Qi9kK$BJb|iJh+5X`Tls`>)${szk?1(4=HeZ zVm!dZ5D!I3q&%ffB0+Z}lyI6uQSnS6PI?T`UZdVQTKuE&REE1Q@_|u1J^Z6thP2g+;rebr9L-V|Ng@M6fIcDy6c|= z$1}D{fdh8IsIX+~UI|(zFK3x|nTk!$TYFBL#r2CM=G<>?G8Hw_US!q=RPuH6Zu0}= zn|<=4nRZ+{%>AUAeewlkE^p%dU&Wk7=U?EHM@-crpTT7H&~CZN8u4>7{B3jjo&NjH zgHwF%QT&}!aep_-<*I=xNTTZ7)t(p$CO_+VKh zb9~=3C(ILgSas4&uU(YV-#OIqlQ(Ys!lg!kmQW*e&6lxQ#M3&7m3r$n-$f#;%`K44 z67;K^hg?Uz;zt#7zHA;>n_8DdRTwN4w_2*!EFUdG;ONv+DJ+itt<$1?>!j=5aI8T`eRQHlWX1QA(pK2|Cr+%tN}SM{9fTzus~ zFlc7hrms4*D!tk7`-*Aam@|GKonbPoS8rC{dBB*l)vKLd2LmSHq3k zjS}~Brxq8pgN-eXt&MGs?TvFA=eZ)MaY5rkw}37+Z=bb>62eYI?fnhsH3S;AH&jk& z_LpmRps|L*hF%O6gAG-#sG`9+vvAv~EH9oAnugU4e$S^@OrXIxSy0iSR?|zu1Rp() zBzS#wgfA-M*n9AZ1MfS6&Iilq5w-9i5g%WK9K&DBbw~Yo&S^C#&Nk*J;1zIpvoX(t zJ7dN?2%ZHmf!kY*xvzy6Wo8k%PPBBJ=QJhfkh-H)KUer>nORFo9dFgoB7s@U;GeX7 zaMp787pzqURx3!oW>Zz9&LwrMO?|xy?!GqTb872vkMZ4^zwI|4^*_>PP`unWcwMEK zBFsN^I@j>)=?VF_=TaGDuevgGY##b~xDT9%m#5~f#DgO*&GVVp=8=28k-PZ; zixXUn_JR3Y(o^%-o0sPsb7Ke92KRvz;MorS1`_({ z;1zJ|Vrl_SfFFZb!Le>+{KiGUbLge-D)mzOYoPCF^?l_E5c9k5KYQTy{~YkozAM%L zccAY)bKoc+e)OHFe#_F2v%ZMyTi<1ynEU(UJ9+0Dgb#`P8znxt+20C;&!Q~kTCVN8EAASbB{)Q$1ujT3QmIPkQvcHqUkH)S4PvZXoyTg=@ literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class b/androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class new file mode 100644 index 0000000000000000000000000000000000000000..306bc08c9eca5d510d01792bc7011e1ef8b75cc0 GIT binary patch literal 3092 zcmb_e`*Raj6#i~rn}%%(EhN+wXrJyJ1yVD^C9E%I!J3anCXB^P5es8!I)lWI66^)o8k=tsx?i_5Jhr zc*b<|bB1HS)LS67YB$!Kj=;cj>9(<9aMxz3JjLoVbxOI%@@2a;>4z{y5*h`7|OoVYh+O%QfO4o1j5*Ch0D)`*TCBm{Prth#w+{mzPMUz4Q}=r1)YMs3lsE&1**M%*=vBu|$9 zYh7h6SW1<;Kq^}-j&#+FqA)8ieR@?n7aES`S`8LW6uG8q*jY=oaf(%es6@I%dfSVn zv(Q+tv!0P`aipl>G_}#;{`_XeZ2H)iKp&6In|0H+DvOqRPau;W2@341?;6!1H>Whr zkixb|{N33VN6J?^43~`ijdhnLHSRbGOygZCg0p^-l);=pddu-PcmlIHC*5^vUC=R) zi>!`gy4|2`jgI~{7&0&8&dU~fA^6nDqJ+7m<2{rF5`>wzjSb7a@6n=mujsgn1#fr3 zs8-oAlpXmbqm*)})}&0flJTnR%KFMSlKFJE(pC-y^me5@*8&6H459>gn%cgkt~u4o zsN|y)Jc2TRcU1U$NTVxH?npcCl?Eg{%SI6h5F{0&o z)7oUjU6!MozHHXm;@*f+O-pX{HNz>ZwPKaih52$ZQEsf;74w26htcrAd@hd4su8GI zXAc)@hU1uyhOY$d8UNr%n&HH-CHi_6zqye44o@=*z{PVb@Z)f1tb+>EBaciuR|=k1?2wKSO3I z9Pu`X%G~ws*J($6dq3@%Zy%(s`Sx&`7>9GCkCFXdrIF)ripc>PL}+D@W+M!tihUSW zdnzG};RxTDn*2gAT_M}aPkWw8%WL-J{=nhP_|W)odB7G3$edhaUdQ*KWAsF1T<27Y^XU0o+Nv?Zd4QAwryFc*e`}`OMFV zTp4=A{Sa@|i&K7#e&v@{Z@onC<2@x4Ui!%(Ueb>jqQ^Ua`W!ZXyr0Oad%yoA7YEc!`3B%a2k(zzCHOvVOdxy(=tOD!z7 zU<}4O;rmqXb1Yv0yKzp1y67DZ?w=0$PWyZlnELokolRpEYl_Jx_d0zSF@PHi|BQDs zxMC_`H-&X_Dw9hoPNk|+iqifgc5Pcixi_|o2`T>*>2q__UKP+xYK}bymQlwB0tt@eL?4@j#dM$gCw5Rfy zxTF$Dh%-M5F?QTUl~BZGXLo1jy?Hb9`_K2E0A9f=Aj8m<;h7}^?gwHhmF4(eD1~?C zM%Kr{Id@ejl#_^u1!NgEQ?KO&fpz36F&65IA^%4BLcL|sT87P#?MjcApy8g59P$k1 zzVP|+=wiUbQ)e*b43)lgouTc7B7UczS@lIk46XkERn%rEO1~R&M-k$7tAAUZjI7Sc z_lCS}*l`)_I#yBEt~Ia{NQ90pY%{DzTy>?dxUX!%CscQDa+z2K}?} zy*QwA)$?MWo-t<{)3+7-+66pesNYsFp$2kgy}JzPCsx=OQ9@F{Q-;^e^rh{-n|kCq zf#P8aHPqvtK4+*d^tv+B zjrJPI(2e$v&H}wGvW#rbyg~6>;x5q{yMZEB=+tKcWbf09HUnik7hFe?wHc=!v|;~%JfBGhLe4)&*LEU8rl#kHy a5-nn^QJw*l1Z+_Sd)Oy-h6BRN;P5Y5N$Z;c literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$attr.class b/androidgcs/bin/org/openpilot/androidgcs/R$attr.class new file mode 100644 index 0000000000000000000000000000000000000000..f69a8e17560897ad1adaae18fd15a3f75ac850a4 GIT binary patch literal 358 zcmaiwPfG(a5XIlL`$yN+*6KwsB6v^_2G2?_g@UjsROvmt8`hLHDcRKTsA1!MGu0k9OlKHP>NSvbYLNg#6AJ{Bb5Pbt2CkTT036(JxV&TPFV?$y>LNq}`Yxa%}EUvp`Z%<2qla+~uKfoVl zoI5FOjLn<8*|%?I-sji*2Y@s5LX-#x*3BZjlxC^4^^q`BXVr9;q|x{&vD&&26+(L< zo+ap9r1F@=E|(iJs@m7Yz`q7s@DqNhlxp zCxpttPGucsv>I4PgU}i&Bd@c^Sh_nAYf0#gY$EhTIF<8Nv*PC}B^-|a+y0zTzqOf5 z0mR{7!2kdN literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$drawable.class b/androidgcs/bin/org/openpilot/androidgcs/R$drawable.class new file mode 100644 index 0000000000000000000000000000000000000000..43d486e461eb753c8772c3c239c81b3a83a13216 GIT binary patch literal 418 zcma)2O-sW-5Pg%jNsXzk^|M}8upSJa6)ypyP!y`f z20aR1-pm_j-n^O5ulElC=hzS65e|(lVzZQbsY+AFLg&_~yvV9}c9dK3Eas&Q&?XEP z;z`7%&_#SZU&yQ`v{hy_fhL4rVsuptU8ka4$<~Vp5d2G}ReeQhos3g%PfRXDw9t#N zhLF&oDlKnTk8^47-5$blYBEu#!YapqitYMARfOZ|KdfF5!aK9FnY>m`(4U<---KwQ zwX{hos!CP?b_oZ6%MrT2xAUXeKR=8xLI*y_fSHFbXXNf+T<1#MaG-PghUm3v*Bb5Pib|rwD@hfzTN()WVCk#^w?e5~2wj`n_X=OO{=-x2Li4H(8lj_yhb= z#<|17#@M{cd;8|?%zS>me*iegAVh_5VBIXTOKFx$TOSECbyiJhX%>x-w0O3;4^bs_ z=HgLAT9{dMo6KeE3Dt#AhCo9?E4C){!uW~MxeQ(cfJIvx6K9_?=?aku^-E=xzaj+3 zClk(y?Nl}ppxwjG$;Z(tY#HxQ#8R2mB@AMah#+}Vw zDz8-$S0A4hs}Pz)W2B3<$TFFQ*e4AB4&%PnG5BsgJKwK@K5D2l3rn`feEk=1@Cy|? tF}Bzdl^m#@zG3sVZ0Rr-0YDF1jD?jA=wh2|1v@3~Vvp-8uE(GBzX5PkVHf}a literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$string.class b/androidgcs/bin/org/openpilot/androidgcs/R$string.class new file mode 100644 index 0000000000000000000000000000000000000000..d473cb81c8c6db44be5035f5848de2cfe8504c66 GIT binary patch literal 445 zcmaiwy-or_6ot=)g+&BG`~@qc1zNbV*4U7kkPuDK(3)YHEJKEw&CFu!Gg+Bf_y9hX z@$O<_V{FdNH*@c~Kc8Rk9{?`V3sE8*TbD#Ol_pi%W|1&6XVol;eKbDxnNubS5fIu7 z@hl=OOcLEs7c$NWHIb%IMl2MXk$0=*RJuno)$H3D*;wd_a4P4Y#~_<4PdFL9d9xD|%C^A%sO3SgGdiTks_zeO>@9G{XprRHgYIaOv)g&O0kk^hq#v3*V9-6I3;+NC literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class new file mode 100644 index 0000000000000000000000000000000000000000..95af7d70364676903cbaee10411198d19f52394b GIT binary patch literal 1127 zcma)6UvCmY5dRH5pqx~cTC`SeYc(ECyLY?3*$?!sgtRH;fJl6cMUw++nG)jFPb-tX|-Y8@Nbv)=R|5X_(F<7fbN%xRi+1H?FWA=W2N` z|6he0P)RYfmE(^oz z_4#Sbmr+KQch9pztl&CF+=3czFqqxlMBPMj{pDw literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class new file mode 100644 index 0000000000000000000000000000000000000000..7234b135ec1e4b601e8d271c48caf5fa07bd47ba GIT binary patch literal 1440 zcma)6T~8B16g|@xT9yi0KvYCl5!pqc@zolQh$c-cCi0OOo~G@z3~YCr+1*Bc^!NCn zPb8Y?yFbc!XSei&v}&5n&fLBC+;h*F?XTb8egJrcViqZeRi&Fn)fRqRdMYeNyc2To zta$kR=(Py>o9d~kg;``6R>meKNeq)uq%Xs#46akIobnDYdfaaoca-u3_e%qz{ZLE4 zS#pmUGA~qJSV&_kj|ogN%vPi?_M%o*=mTE$1Vf>sYTP^GTAFh=mO~hSJb{-SBuKyZk~(nmCK= zG-Dt1rPfO4aD(B~p|3@typE{bHPs?Ncqo-`x3!|NTaRsPs@!UOvL-`2h}uF^77d`I zTBx*5h9y2Yt}O#Q^6R2OLe{tK*HIAK;(b!-eXyn9QD?&Dz6wu>SCOuXS2DhnLm$Yt!N*+?6n$Dij&^jJY0c8<02%sGbYp3A>m0eSv`@jJ)uJaT zFH05EwA)DXkjE7|8Jro+5{lVf#kDv)hXUrPkLfVq?eLb)ri1kz3-1bx=eYTkPDu~L z!gT86TRnWMhi~CFp&B+8mT@P>UxD4le@1aL8S7I|U<)y$+}uUfX$Z$cQi`kN62MTHGEKoAzkPkg7KtO-*~Z->koUv)?*s zGHk2=Pg-VJ2r=w+)IP&pv(s&7dv&$j)EIW&PRAFk=$2`lew9JW<$DZ~2C0u>HUUbe zAcb2D(aJbvIj2ra(tOvn2jy127pK@o1+$38APZwzfsCkF-Bu7ooTyaOHaer>q2V6z zL(5=DtB%gC9(PS)2b&2AV8KBY?y*K~c4c%Tm9BA^U4|hc%RjHW+oBJb|oYfGY09U4wTBTG<%eDz~6C8@S58U>)4dIU(Vi4Gx8gysb1C{7`(N4EHOzk&7B z^U?*9=ST;}QY0`kv){=joguCDBWK8H=UDkdh#9QXKN)0O!aOoq!y*mg5rbNKoTEfB zLX%wB+PJ{_1RSLRj6q7Uma!qklF&Q2JBGiYLIiyI3@iQDQsJs!5sKQ<`Xx5EKa=NL w$~7Cikr1a#e>~jfxNVCEvp8Np&J5E9&;M~G?Fz;YjAPG-z1f|;QZ!=dG&j0`b literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class new file mode 100644 index 0000000000000000000000000000000000000000..5e520fa0eb6d9ad0cf329fa2572250588a3e365e GIT binary patch literal 1333 zcmb7D+j7!S6kVqQ0yMqRN-eF{OSM2R5w-OK(}AH;8M$@O@?7jBdJL~-T`Q-vY3eQE1FeF=cQ*O0&t8JJqNA7CJ zj%I$4tGQZb|4?r@OV##)=IEu?fiA+wFn*{VYqF_XO0l;66d@(I;7`VGrKx%#juys33MX^(;{_CYt?mSm~0 z+UnX3{e{5?I)3Hnbsk7vsz%e&oUTnDw>*42IWvsZEh;4yEK9dtZF)zpSM@bu~ z{un8UQT1ioJti;TaU*yXU6sC~6!pV95|b+nXSh2c2~Ys~Ns_x4vBX=WvwOJTPv4|c zJU!aOV*Ry{yr^fm%91dDj^)))^yO00B^$ev5F*R0_c@Xj!)t{jEO`$3JJ{dz1Uz&( UA5lY`djp$1lkyp!;8}L=7v>5tU;qFB literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObject.class new file mode 100644 index 0000000000000000000000000000000000000000..5e228155303a29cd063056a485473fdd564000c7 GIT binary patch literal 2255 zcma)7+j84f6kW%5?8X*pE=`&XX_}I>veMQKv_P9Q#7R;+4w9T1 z_>|5tJo3T=x1xuNphhm`24GkU0s;aMRcmp@72&*p2M`p|R zm1_-CS$l;9{*Spz>^C)ZB2Vx9#};dkpPtyBh>m6`QpO3|?M<+a6c)%UPb|~6zNH`; zy;`iPV()0k;fz2hS*v+fQg+8J z!xEPBcz{|C>jFLT$VA&Te1cCoA$z9XlB>WYy!s0Uo}q8VIKYMP zQTP*=9zMs!UqN)>8l#g3C_aln7+3dEG8muU$E~>BaKL_)uoqZpjED6i-o`lQd2J{P zMpzJUF{=K`xXq4K7v-SyRPc5OGt@(17I!16bEK-iWsQ-2%*FNcL3EP2mjnEPa90~Y z8|cV;n+%l7O0^Q7s$z%n8|HrGOHwI4fYHJY5sVQ+`Vb9;X1Uy!)7R{#J2 literal 0 HcmV?d00001 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class new file mode 100644 index 0000000000000000000000000000000000000000..f4a6dd7e4e5820644e459a4aa5652e5f2a69beba GIT binary patch literal 5422 zcmcgwTU1EyNGyRCT1^jdAVY^4dKk#X zrZ=&+)q07yCf1rXTCAy>YBGdG)4FsmSAEEfk9Fyr%NHMf@v-&W=bX7P!vt2lmMd!w z=l}oxe|zt5U(P=H%ZJx*0{ATcpuwkbZ`>Yjj!#&ziAXe_Xr3~s6K3>@=H6X>hX%*2 zp+uJ%Ge<33LqMTy%$zoxqh@Th**#RaqifeAN5kDcM|O4Z-rJ*~!ra>(k4+}bSfbC2 zPFa2`(-pM112;*OP6uWx5s5Z;MkW&>g_54gXv|DZ*_OiIoa6Sq^%53`cJQAHRPr%n(k|OJPl{bSR-s(vstlBf3oAP# zF{^uOe9*Fwn1fN;TG1IFGNXN_9g(%S8Au$9(9OEeCG7N=rKzR1HA;n+onp1^HkbF9 z3DcDe)w|R<0qKaxqm~&9tw1e4tzjKeGd_ts2G(PPf)V9&n7YhF+*YWm3wtQ(c%%*q zbua2PY*JXg5Go~MpdJmRHfEhjD6Fc>w#PG3%-L+93HMQMGIENfF&<&r{*1vSyr1h) zi?=J&hGgYeNW&I|dzK(lM+;gFJRmxP1f%Nk9v$1!s-aC`eZlJ)Dn+{8z~{hxDT_?@ zL}H^+E9_+P5KXRJ;981m9iK;shFuEf4nNs(Ft8hY$o8Nc7N-&%*9YX*J_Gx4fJHGa z6>?~V4A%{0vzJk^9S03Oh)$LjUF)(^!B^NsqYAo~5e$iM-3AT`Jtf2tw_JX{VBjIJ zXmzQSh#7UlQ(qTe7HoZ=1hLmZA0DP>=J2ral$DXGBpndBeo4Opg}YKr=BJy4v0HNP ziw3?VGBu#We`;-_<|@RcmW>ib0FsDWdM z&{Vv8>7Kxq~ z9b>Siaj~&1AlW;w?+apz6((MY>~RApaFR{XoM3BbWSX+|q%P&@@ysS^WB9Uxr^NqY zBJRp-c=~q5lp#>ZX*?^&KBo|3Hsz8NDjbEZz)2JozG7eoUuEJlzubgU*l?Tfm`XZ! ze1Cj!Okv})lrga=9cCY@a?Q<8Pcji<aZ*y$YzX`jrigf%Ix zN?~1L6M4>eu)NJgcbG*{9J7u)x7;0uHZbIvP&6KMva}+fZ?>0(FRGIhsh3q(0e3&{ zTel?#uYF11MN?n;urM?G033LX@ zn_L7wlQo|dK7-`J%R9i$D}~lY+QRJ`tCx>bnQt1nh*^aP7K2y@1{2p!*o}4JWr;f# z%6zX#+n;(tlOpznyf%|N*f=?`wAgZzP6+t5flIi|4zq}AI^>v>ZX?uvXL`cP-fhj_ zU5)_?2bQCDc~C3KDCgQNIv0J%gvIMQ16OcO29|s#!}Xm019T{?;RfgBOhoqDcH9o) z_X;h&G25DqN2jgf+M)P3zdFoBBp$1su;Uz|$J=W45|J>6j>$+(5l-zou7e#@?}<;@ zL)N~CjNX;GUnuv9HmswG^2Ompg$(yxY0fIh9S-qauW;4|R`Qu20{mUcolf3T{JXkg z4rL8x`c+gk+`y{-Ijp{lHSaigs`*=i0DnvQD`*BPQI5N~W4O0bgSA`%pTgZPvfrj1 zC4josa0P4p^SH-{u32?*^E@^xyocKErg=0fysk!?c-rjaUP}^N86XmpP}oxJ@2ROh%z*2VG@utQ(Jku6v^b5U*8@Ty=gFHU(ATh>%NJiY^*edasDYumQSA`AO$|-gy zHenAo<1jyddeMvle(jjp!l7y_p5uJ^BHHmiesR2p9k_rFyu~kuw|Rq+z@M-W?{ocE zbm8yl#y>f||C>nvMVIn%Vh^HMm2vE@B7-&PSDQFmx8PB=jq47M$z2#$y_|R-!-%rD zeiCEqIHKwqj-oTDRj*)LoxySSCQhh1oKiROl=>r1tM~D=lg+P6O{iO`Z06Go_!{$h z1*KlZORS|T6~)V}06z|^E%-W512ENkd;_mA-`~Oq_$K9w=}kGlg>SP8KOi69;f_Xc z%5a7^g0$N^RR?+cT{)%QW#mOp&yb<-;|K85#x)Ld06!$xwbbfb@@m?Wv)psFo+Aom zXmsn3bFhzRz*?`IyEc3IC-umDko1@OcBARm_Y8u(Uq-KM=&#hb=p;sp5k9>@uQ<^0 zKM8(B9(;~v(goa|v)ln=`(yrfJI?D)pJ}Fq^qC^jewhzGCyAs{f%IfrNl{wWPqIMH zJ0SP-mdFP^mvV8=X5j?WI2W>T-dGmSyNlvn#80VRn&v(RU1$k5H2T*j@v~ez{*^^t z#*QF<&Y(K>J0TaME;4wzn5t$m%>NX?`~}0Fi#h9I9^_wX+dh?JA&W>DZ*Wi3O!?9l z`XIPsq0g~ZyuHLSO$GIr4i6!+ATk0zcg!CJ@-e2*%Ioy0V$Ec%Oe(LE^=;=`CUc43DoA3P(|56;6 literal 0 HcmV?d00001 diff --git a/androidgcs/bin/resources.ap_ b/androidgcs/bin/resources.ap_ new file mode 100644 index 0000000000000000000000000000000000000000..2452fd26f12793bb5445461ce339266070961506 GIT binary patch literal 140460 zcmdqJcRber+c%D=GpSBdWRI)}kv)@0HX%DZBeG{!h=^<=BQmnGH)WKWj7Vno-aF%W zyy^43uJ84`@9TQp_dmbK<9F8CIo{{{HIMN;j^p`CLHZOnAqEx(3ZorcNjPp``sHOz z3=B^!3=9Gc3=A71TQ&I}VN$j@2l+U9op-kwWf$&exwO7=?xuMHGcT>6kv}V9O!GdEkiwp%Ny?<$?|v)hLzm7~z0dOKh#YX1 zi5!nf4th@B=qkIf8og9Q+LvGaK(c`-_L-;rQ$6E?nsI0SXSVwKN_{Kco_X>w_FuED zXnL#-Na>lZ{6 z{%sY}%T6Jju!;?^ie&%3idOn&Mh15JHdck*2Ur{aXoFo zXD)nZYWjp%<>|PB8TIInfo!B%2AL2hlT2`dl($L1r)KFH>($v_< z*6vtj!#`Vgi=zFGio1JcpBPl9~I+NgaN^QrXP_BeE!~9@)$iw(B_HD5N-7odmLEIZcVYz0)Up~8#51zUB ziGmlKZwJraGjWtCgVgk#;ORWk3pJj3qoh0MNhZ{LGxrz?NoK@jOPp)H${+VD%hQ@< zekS9U)A){dr*v=1{jI;fsUs;EMY-p1aizNHdOe$@-Y1r!u6%kygD0~W*yUuFNZjwkPrq;U(T7;_<4KkO>wtqNq2nI@9Cs zUHs+5M&hjOW*^%IeUMy-bGl2~3zxZ?Hw}IL)3>%JN^(h~AFI$RExy~n zRQ+UeCP1gm-Gk%o{jSZXnDgjn;!_$_QQ9T5B@OB6B0&|Ev|B5Ar-p-1&$G%4R<_Q5 zED<*&?dW%Ie0zWOWhq;^YphMHm;0p|o}*;Sj!mYLE$f>ZOxBq+Uw=$#ef_5DL1fAF zU3YV@lWuQ+%WPLev!*w$=1?hXvA9L=8TUcCbRyTXfw!A#<#_QT*`GtT@%z=rpLBOa zbo%D)PgR>~HRq{*Q&`KnpLpLr$3}#1B-4#3tuA_`Q};x3K}nD8-^994cf)DWTzFnM z(OfHg8v`R-Ry`YA11t=@<13)r7?_~h{_y4ua_ip*?>}$g6?y*@o*D4$g69SJtsp!} zFl;c4Fl;f{Fbv_H9)=@4^)W2qyBqMYA>3mM*Gw@CFsv{vF<9ZVC58#y|KHvBW@rTMDL|_h@Ebb}DvaCk8Ce}G_|6bMOJdx?P==mR$GB^?z>D1V&|x-2MNn2N}p02rfnjyrSS0kD>ANs9)kb8fmdWK#PH;Xr#L(x!qXC-KJdhbR!;N*dH;_D zVqlyOYqKORp1dW-$9 zcmJ_YuwJK-um9(ElKyq~|E?Wmod0t>EB|9V$o!DGBKw654*C4g18H9iKK%1Nvd2{a zT>Nidk##(g+2hw!$o#0 zH~;jBT>D?m^PlhkPy77a7x@u9ka;3~!7Dku9Q`9l$alz|A&-Cd?Vs=d-*R;FyZ`zx z(l+9w;Pn!6?ce>K!QI~lxCIy($dd%FB6#1>M$b`C-@@p|W5cJWY^DZQmaI=LO#&3; zB+uiL;KGm2OWhM!g5~i+o+xBMyK+YY$Tmxf-+tiqYhlRIPHWR^`>5ls@EgVGAC@@uo(eW149){cf(}I5ngqovFwx#5-ysmwG z{elE_y1bctsbKQDdWli%^(eYmw-&e0_?;iR+f}qZA0KZ~AYQRv?s#jPbHwJA0%Pja z$7W_WQf5&R%uLh!wKgJa%K^xSdCqXt%=)B`Q|@kWA1$|&lar_X=4CgaKc}axtQ?gZ zcP%HPNG9yLIU)q2@$2_pw7ZtC9jHl4O6s-|)}^JTyxufw&f1l`_HM_>4n?*%MRNR|4AFds|O4a0ZMDAs$ zb7!6vfNO8@)sbs9*A7Ix)acZCb&s#U-w!*K?Yao<%8833?H1hMOGuTxM)x!rx&BDw zmDFB9Dy6-h-AZi$vF@Z)cIKZ5gH4a^_}cc!kD&KW1i{1`iMHrp2rymoW6K z#k+1mw*st_9&S=0p0H9CDoO%Ih|*!yeR!z!XE)fPlhw=zZfySUI*;Q))lB7zT=YjJ zuL~_o!o5UVYpiAH1h(f#)U(ot=aGx}vq$$Trp2UxH_BW+pg3ub=2!GL$I^2)w`qN* zr&ENP(~dVmH1(WRMRiKbcxkjYs$-e{7i;s~T%-x~WeK_)dsRb{B8BJ#k8h*&`EiWM z_u_H1VH(2oe7-A%QIV6)Be&*+{Qc^f#7fW*&PS ziMZMMtbCn7dc?Rnf9LJ;b9_W_aHak<9m7L?4I@d(ukN$;v_8zuh~i`D51$!YmOuCV z#>BBrxw-s&$;3yDnv09eNQysK-h-7I`4ts6Hr=Fyo!v&YE{4@RJmjaMTI_F^Jt-qZ zdoLb;+<(XQ%GHj}?rJ z-rLyNM8wCt^^0^bZ_n?nj?XPE^>(I6{umm{Az+YWM5EBW7^1ML2L9k+Q6X(@GVO6Z z^6OLW%C~QS4%(MX>_{IT)*%;mdsykP*yVNV4Dns;<8_Z=^7Zwt*qw?~(bgv4GFWw~ z{#9ra;;=NBIaKLrZf6%kfPK6c>^}+$3hcUNc`|Eibo}(h2Ul^P-zFDyQV?)l>M40L zaEqP&lhmo>CdLv1z)kbg@p&Mu9Xf8KR*{K9q+$qU}R+E zdn>nb(w3H%m%sX+E)DWM87xy=TwLULUc1I{83PfI(e<`iPRZ>-+Yqt~l5JIKcV1kW zed{=^C@Fa+#Si0nV<`W4a^Vd*jlZf`s+gy-$r*h>OhVFSo>!gbIP5GL9v&WVcOr07 z6^kVUMHc-9WllM?w6uHml!r;B!!FV~dC}n)k7qg7*Y#ey*kyCB%ykGB(`CJ#XLBmf zYHbGhxCOMwR9kFHp2xxbO##^rF&P<|naw`kzO1~OmIq20{!ga{2L~z9AnDP0A3rK= zk9gFwT#?qAew6=kV%4eW>2I-DuU=)AmPQAjI-XktYkGI4B!#m$Yjhy{H(Oq^H=HKH zNDtlV^7AllAFSg+>38Im4uAOY;kx$@wv?3A8xfBh+;iuCba&V9iJc5fU~O&9ZhOe_ z>t@C0bD^-Ry}hdHIjYF^e17y=0fVYdMjX7%q=eU55!8HxpIqv<;Lg!152IoY z)g#s@v52i%f4iJfRTVFafvB+P#$ym!8yk+>T4^ALLL1-jAj@vZ9d{P{c-G=Ije$f2 zb%f3yMJod%hb3KIU8uiTa^vI4BBP=%H4rkhvi1_l3no`o@YkIfh|qw}&$HpLUnl)p zstjRDJ>Gh%wTCQMii?WS4YxF5AQbL9dhb(H(Wg(;2M@$QymgYs|EhwL(mRF(CovE> zAI#%5t;@^I3_u&d9$4%>bx|;BvNf9EzhB3{c|#)R zkHH-$t9vk~R&4g;daTUgHw?tKc$!AV#bp&0-SYOQQq#7Nq;Q#`rek3EJC+z>8KPG* zMn*C)%B`5Y{&$U(TPJNYVLPd4cGJEXc70IE z+W3*@uEHJn>SS*|^<-pb!meTCof>8XaTT zzO@G{HWR>*@W_DbSXiH0I~_if>v1;aT1Z!5 zsi8ru4_R41dVACA>cr|!1TEpJUovc?w?C(;sp;NUX>HEkz$>tFi0fMYkd!0}iiwT? zB3m_UspgO6(6j9!nX9Lf(NIy`)FuqPa-)kjMDQJK^gr#bFk;d&d!4oZ&PgCURRBIR)#)_U?#*ravYwtRXHe>{4-Yar5{p>>l!6 z=XC)AP1rzeufV97m<+3D^O_Y?Z_Gh65GjA$Fhj*UpVng7g;+AzYja|u736Qqx*(NMy7BL+~D6Grx{x4FErv<&G*kVC>_`= z&U+?XI^;mwcjb5-p+U3nVpv3{U}ps~|rot?`QoW{-~ zhUR4Op{ZqM55WdgvFC(^hi`trb8)tXIq%xZSZMBoW2Am05z}t`Y&B4~C%Sgu2rM8L z=JDhT^Z4mKZhU!pZ;Gdu3DoFBVB4_c+S6XX#Pt>xhn-Z?)Qo!> z7zpZ#tn93+x;j(VkNaqU;>^rUm!01)>>Dqu{oR!AfZ2Ec;#UIin)haRM%Qf6)qFgb zW=}DHr=mxnv4qx|Xz$C*Gn`B`P08K8MoCEtg@vC30{!I4lMk7h)PJwxrabq*a`x=m zilf6n_Vwp^n%MD9Rsd;BpV-f`YE@#$6vg#eH*@|#lAdQZpvGH8~R|<#*2~NJI0xe%{G%lQF*4=$sv(w1dV!=&-LVBWd z2M-z<9Zi5e_AOFPC-Vh`%f062<`Y5jmj_!E6h>tU!uTO4=M~%CW6fJdHqH@Dip$F9 zGsPDD94C`$xLD8rQ{nV?*O0U_aH$)J?1TEAC{li2M#jB>fBe^g&z zUwS~mSsW~{i-(tSeIwq!&54L0#CnPL)0?T7&sA1b3_Uy;Inqu^N%6rtUL7qN>p&SV zQBiGe?O*u@F94$^fByVg{=fvVBY3aWu`&J2moLLy#bLG4^%)fv8lW9}{T=RUOG}nm znEIZbKYtR_oW>B%-bGwPK>>%iKYDz8+y!iEPiJTH>guZW-cme7nxf99u&y z;a;mNFSHr)Yhd8-a;a;vMklzfNyW;rM229)aP~Tm_T|sx;mP!O$jHj7z%osBB<5vj zvxr>?-`a8z+U!wY`*YxfDb8eTX}NR}iVJ9I@ZDTi!-C!@&f1Z@=>%7~+Wkp3Hs=Q` z-A>gy2qg5_AE*2=Fp#ys?^Zr!DVC^*gM$OA-Z@(nE8`}dc(_V=q$ngL#JMGKC;7FDi%XH^5WlR9Oh!hAzxkunU{kqxc$kUt z=0-n1$3ET|R0yo(4fO&as=AqJk)v{lfb)121frrcQ&Pl4M0Dz!@V{!Ep8Eaz$Ru+wH{W+)mwNbGDZRW3{HTVJ?v z!R%mf6W3Sl`i&ct>XDpDpzvTmka(?1hs_HE->=pi!!t%vO-&M|S70?#lfkD7B0!|; zrYLf_8e(F{(Bq^ENEq+|NHzL2S`UHz4TyIUSgs1kPh>~=itPblq)Y4|Qu!*x!SN1c z3WlmI>EkzF_gWA(%rgPY3$Bfu_-qV+yHuN&JtI7n=o z^ExiYBRd2-3}$nEq0Tf4R2WRw;z+IT^tZRPXsRG&;Nn7H4Q1$q-c{q(uz}bV_vv(x z94?M~GkE7eTZ_t!gfxVY{B8m&^mhSC5`J-!vKJ6qTXinv4ta*1?sy#Z zdF15gvdV4Ts@$8)+8lj;5ny=$yXVy}$9*DmW@2K(#y>sZm)8ejxBk{9#DJ#bUtaOM zZehfGBQ1jr6a8M>?m5i1dl`K^XJbu?$0kk z;6K$K7YSiQP!OKn{w)CIW~Qd0ee*_rYA1J^TUhjfsDbc-z`7sI>wayo$Xi{te)6kG z>du`zYfgfItF^GZKN)hEZY}f!?CM<_sx&Zrb{!qM%tr%>w8CG%G{jKhFfp9xpCJ^6 zkbEzzc8?i=SYY5I5-x6TGX$@Ji^O|Ga=bhmCn!TtTP-GAvy{~`ebc#G2a=8%wY9nc zG9dyvr%!T?p5E-UHx3vmWnEoLuVYa^)VzDw_X?Yi3|en3Ze*W+iSqg|*rr#cJZ8Pw z>M*vccQL1-ahN@fdTwrRtdsB)p+O5H29?=O?OSf&5`?lK1A=bYWpUr@PMkv|V628p zo~WL^$Zgj~Xywx>o64aRy-Y&;b=N%mgZfQdV$uJO@?b_1)bX62OgO*=#F>?q#jtxa z)kP>`h(3UvMAvzqL6FR~FQis8Kl2T+SMk9g{3>}8=i=%*x$0zCI&jwLCEr`Q_Cyg~ za3+wFp+DX`f5~%KSQPB-xo-P3cgu_1$m^3vC%yx_Ny=>jfpGyuD=5R4u`=|4RIUpN zX}fMOy=on@^kQ-q!NFip7elW~s=^ z%5vb{Idg%G3Yq69L2TQl4l6OdvaMg{k%@`&XgxHp??#WZeDm}={ujEL<>kJ;&G|?$ zkPt^nl&8PeBL>;Ke*Jn^f{<&O1Q==0ZFQxWk++u3?`!ToQ&(=i#rIJ+St=pYccyx_ z67d~{{UH3{DmGvb&<#e&xQflA!Bjuc(a8l94&wr>2EoC1&@H>I1$8V;1S1S{#Z9o7 zskGEtF_-Vg6&O8eX4f>5y%CvZ_FiV|+V0*q6JZP$vv?##G1|_Pk=Xe3aokUoOiUPV z%XoQtVHTH`wpx~EfjD&5F-5@mch{%Qot$F6rhv#&)x<0`+jQu>FM2-`owa7He#usN z`11Kei&!ojm0^}UVasj8OoUW|;=YiCL2#dV%>Lnat(u32$ZeTWQK}>%*R71gLS^ti z5Oex)sPL2<7a~a?Ff3pI*B;}-+BR^TS4cL$8c{HtC$O35h;E)b96WlZSJIp?km|EG ze>t8w)N1ARwO(SHf*g(F`^UlO=@U3X$kW^X=;>1h&{+s_gRaQs!|Jyu2x)?t{n**z zMbwVUftWrpzEO?IepQ2xYmgZ_^J{kN6!~gs+pOMm-K6spjzn;)NSAb(|2;5Y8s#>0 zARn;AJ;TFt=8X4T)RU_!utqm*#VWjq z^?cn7;x9T(r;*Is*8F38ig&=Oye7^hGowzW{ccAi4%={}ww?Ymn%JnN!+ z>}FP0CelY&*>BxS1s?>#cUPB^#JTi2olawA@Qqkro)^gZ#i>NIFV}r~SnFo8)v8^n zk*QY1lx!E9-Rv9I{BCsTsxOv>P!RDBduz6eQunj_>icD6<*zu@(@jkHrS+Fw=P!n@ zO$yWpr}~qDEl=U#pjRxnv^_#Jv#)YnE;y>`wJ!A zYZDbjse|4#r6hmy`4Upabo8_|o=&YfK}i1W`##3}C04#QqL#65p<>C~5<+6x9-R0T!(rN zhFfU8jT3j3rTeNqNH_>5fTRyaMGxr10~FFkA(;&RApPLawz;99k0=bOm}rucKYR5Q zTXWb0DruW!Lt>6fV;Gm(*@XGY-10kH3ofyjx-R3&F!BmFMS3>5+E#Ex@=ja6zp?8P zso;>)cJ}ITrc`>6=wgs)8Yae(*n@?8FF(czxt0L@1U)ZsTtDDY^xd4KDy?9gLes-mFZ-hRR7!N*s|Des48=-|OxVs&16+FqMZr)j{T9*T( z>5U3UGC2H>!J7@gui*OHt&H9V>?jK`^}ehuT?CVYmR2^n9z>c52v|ZeeA%}So%X)m za#*>H^Yx5jM*>5=#lZrpj_W&%*~>OpbTb<&xRAc+m~{R0lpgH|5gKB0r1{a^ln>b4 zX0&hKo?xj_GB(+8`xy6jc6ssM8x==)$u3Me#xz+SorEYhT{*NKhoE3K1O>rVG)*%z z8NGSBYq!K2&nS)3F~+A1!}ng)MSn*UIt z9+fJHSltQINpRgaG>Yy4qy(!g;IQz0YjNN#4Hi??7TX1e6FjUNOxW z30S(d6dTw#Yug7ZMen~KEUaaewz=IPcdj}j%v_dPq?R^Qy5>;M7YoV*GO>}&Y8+gw zL5C|ZM2>wue)5+uUy7{9CEf}+%29;8=&Wl!5a+~GQBz}PV32g(T2Q3=Bw^;iYF?9{ zf79|sDT@>i*fs5b;~x;J;RU_zYzVmVhIcqQV4NH`=oJQNOTK(Vf&)fvG$L4f(S8PS9iBPB=tGp3E!1V5X?+G z+(-uzrp0T>E+eJh|1LYDP}KmtEsZGUpqJRT^#h==S_Y8U52{=tV_W z7xcUfLg{E-_gJcT4Ldt!+?InGg(e*><^!K^Q>h# z=KxBV$6SEQt|&M8+z*k{9rk3?dbX|VMH|)RQj#v0iGTCSmpL)3W-CB42Ha6^j%Kmz zwxzc}$I#HwuPW!lg2F;B^IjILa=gEIabOV)xJXDED3&Tt^>dPW7e%FeTWx${H_vx$ z-NcL4E;Q_TlLh8vGPhcJE4!S7&XAEXM&Y{vW5WEEx7nr?bUcGuJ-y3Kp|zs)ad8TV z8y988DlWC;h2JPtJ@k4$oo7FaRr7#7)~-+6u^FlY5;0Z#YppWTfl4}gYH>VPy`MgL z0^V_=)J_Bc_fbr#= z+Z*d{rKnnEE|~s$nNq|a3xldA_S=zc%%9TxCpxd z8UZqwAXbDdzB-h?(x=*fug}?>zj$%pMC8xa%GWf;>|#4ojTZYsUn+E7>lL&_sdE|# z+$Op50&JiSAxoI+)^)@)hiP1|AA@DccsHaQ89!goUoXbc+N3q1n@X*bDB@wE zMoF7SEIAYI?w89OYgHMoE(T@BO!-UT&JSuXwM4bXf4cCbn~7aGsgV3g9KG`zVt6DG zE*`VvCMp$*4s~sO=NNi(?`%^en=2(P+O{t)-Omf< zD!=E~p9TPsdv&LqSzYl3~VJ|H#$dXJ=8AC2Eqcr;M7~luz!%&@9_SKAq z=26+EllUH0^pXV@g&!ta)YBR&DkqwBuSx3%r@r&3eL;6qEx`6jD^t3b!KC>I zhd_7P$9hAj19`%=5CUvr1x?K?XdSX`NW!kZz8)K2ew*997D+eJN(MK90?pc8YH1v{ z0-4Rri`FBCNSFrM7Hvj$rsdAk3DTJ`+VtCgT=x&3lK8ddsu!5FtBCDx+VltXV>3tC`5mrTz9C=sZkb)ELg$k z3(R|2^U|=SHDQ3ob;)()%Nd4mW@8P#+Z2`7`hoi&J%swXk-r&Dd|s>^1p?xB)qspXF$$B`URUa|6f?d|QbFI^%>>mueh zVek3G z`8}!ins-HDdnFaKWP%M@dr_QgOGi;2KE+pdtN@}xW&0{+v3vOn|6DvnSy$dqA-JrskQP?PK!aAqXe}K0ZF(<7eeVk_R1}-ed1O1`5Hdojp z{{pvcUEDp|?9Mk6j1N;Id@nKs%`V}-h;@w4_!C+k~#PF*Kx>L zxoq{D^b1o`qOh?b!&$nuJdy{Ptz3&0Mgh6T>uhX&z`4>a72Qcsnupcd9F$@7#9JKw0BMz??J-nz^ zsG-0X7Z!fC{bF=-GPTgr{yMf-$W>zE?~pd6g>nsqM-u1Q#56SCfZoD5=xY<%Zi9x9 zo*?X(*_rRBTcs9m;)S;@Spfc@_^{)B$y~KHN}ZvQR)u<`%zHT5ROGa|S!@_dZEg?U zNGRY0nJsbF8pfL?N6xZai&Q8#DsXB*)?ns&qgV9okHeFZ8mL*B&^QbQ!W3X z+VW;9w0TPD=~%W{4bvNMLylH;yZ1_0gg;EA{V|lzd#$G*lKPl)aJ2(BIFTCVmXx2b z2uTxUR}MD&oc&0Iq2BTulK4j4aaV6tH7Pw*S8u+D^xV`plDS%+*ZM}4I#58sQm3?e zE`lpZ=3AX=x%rZUSbuRr8X;sRE|ZC*D2$Fd3~}%&P3EfS948jW&RItqWuJ9&o`)`S{-DpE^>b9^vaRoFBIlZ#9&Ux{;#sEzAgsVS>Hy7F?UUhs(q}%;qcX9A~R3 zQ5^PWNqKIJn{VxnQ9(hH&@X4#;m(~Z#R&6z#vFYr}D;pz##5vV+r>cOgFJJ^7}QjNbBb=l*oQ=%&5-eS89hSaF$% zh(MgU8c-bqy-`{Pp`rLl1dc{!WM>C;)^&u2h9;+`UPCgY>}c*P>3Sx@o~GcVl+8k{B^?r|j)l)qOI{qyBTI+{-PPIk!v<%Gb0g z1=M&f)4BbqC7#z>Ok}rNegh~q zs=|pOqQdnM4!2xr1(Q&z@I9|^;7}!9XUA{@_AJN2t}TT}J2#r$Ly%IT|O*2_31t9oTJ^AF?L!U#fiWNiS#d>P`Ko zlc1ok`RSe?Kk&t3Acu7cE3G|KIeo*?W82YXD%Ru{ADprY9(|HxY%#=tu^Wbw=ILj7Ut(1OI@vi+WL?4CQhp-R*_Z>JJ$aSFcWG z1pWK9(+y;sNe!}4?*WoYY7SqPXw1KI`LZcgitfwEJOHQxmcwpsLJHE&)->tgA&vgy z`*%nJ!`$AVC*?+C8#ny?8S^(1`T(RSlMr`t$ms$L2r)QyP}U6dc9$g^NNTQGEHLQ^ zZ=Rwj5HBv&bpP<_=WGUVFL-&V**sfG?C$O^c3Ra3EQ$o2P<|Nqk@LFDtjfs776SDy z;J9^uetzaG7Uze`N=@L>0&x(as-XUyypf4X>+<$`4Yn`(=*H6}ABjqxh~`ilO&2;Z zs_Qrml3Z1*l-KTlJ>`^Fxx^1n+I^w616YUV=2?)cvj^baTd#FGyg3zuB?OjB5JOGY zmV|$Bjpi|l5V0OLT&Ec9og5ZmkH-0W;;nrvJ| zWaMUmZbKt2j0&6yph2Bv1%Jq8HF&ItY?x)w-;LFdg~%2k_3q2eu*t-HNbp;{bGW#6 zV1V40L`?D@K2TIl21bslzP=dbqQ;;9p>G3-(Yg&ZhzumY4?)l2@AS|vFWW;N|Y ziv(mHkh1IZ=g;H!krPpiHlPKz8PBY7B6qc(O%vW4N5#4DlU(qXm(#(TG`Ula&YQ( zObjFJ9Yk8zioghwpZ*sPx+ZOd=|%M}eqh&Qf|8%)@>dN7g`}+93bXs}styh%8k(Ar zg@2cjKmnEDr#Isr$6xUjIE%-Cd)EeQPK6RLYHpT7vSv_SMJiVV;<{k zZR!S-bGu);+-JCOB>qe^nZDLDzRgYZyAIDRf;+X|T~LC1RaMg< z7o8UDE#}`bO*+%{^Rt?v?2T}`o6(|Z)$oJ2BtxV^1HagGYqWrPp?q|v&q5WbMo`;g zfhuf5LPFV4D3mDrAp#b*3TAf&H-5EP!ft3}$L&|mvq}&eC@M`n-+g8Mrv*0zbQ$I4>LwitKbpfC z#+Tka1Ue)Db!S_j&Hw_24PbO$!hY8UMj1(qLe>8=VM8BB?7Md~Pkw&94gA-0n1o_l z#JV2oUoO_NYP$HgS(aFRX(R35;>7uO_p1T%+WNXZBw9O~mVx1;0OfM1PTK)n8RDUa zcCLKm_BUmJj77SDTYDFhW7H_|8!%_coy~zSfo-$lA0Nlpq7Rn>4g?U8$7sNk5V1lE zEdLZ6(=BJYtp#Tene2hjZK&NZTvfk4?j_GWT>k#^C-3|DGi>7b@4o~paT3rlHn+CS z3=OZPV!961OEe4w^;+} zq#H!Z;F*H~V;T*=;Tnwhyi-gjvGd!=<25@w8EIFKgGaoSo)*M@u)f8H&6j{GL@wlV zYs&JMTCP?mIhh-orCa#!8l!x!@kJT=j@=H-@~c>FQV`%mPerK){nPLzbng zIU1LVlq+cZzq}$X_Be9)7L~z;I0I+}2vb2-mA-Up zYp%v`4P#I^%G=3;4jLw<`?t)3O92~$&&IcxfsOw0;|G%MK{x@2vDV;G-v~IeB9i~x zmuSq4fVLqWDx65I&4N1%AQXMAe@kntGGI2y5AptnS#kJyzu_&HC8#EaJRNN~t*;C_ zU6tf;SgEUa57{!*`$>1y_$t@05s=a^z9vps9W}gYM-=#~JkcdK#oAqk_?VaT~pF_E~E{9qC zrR&j(g|ydbs?Zc8gesID5K^T_{O<0q%c$3x4I<#WDsC^_DC`#;7bqJWzd#|_WX$0& zfS{3ZdEu+!jX=ng0!t8YsDQf3C5D;kCvYh8_VD1;TB48yRatzN6v0=4cTLR^DN^2~Bu7Tr4bbm74sN_V;Jfyq2AMZtRjbV! z&HOHer>ocGOBRwC!x~d%C+_L+IJB(>0>jPC3P2)}v9Zl(ztHKOrxqU1OVdTXdw;1m zqNDwThTiA6-A5-gNT{oTyYbH9NnEp`l9W_HZrK>Fl#-*Pqj>H`&1x6>hUnghJpBA0 zkO~O4S6N?wKNFlmfWRciNeD=e78Wv~HStQ7xb0x<_f?x%IbxO}`$jDuGC!-CfHlciI zs|0$tad!91t&MLX_ESH;5)#idpxw4MFU9m2>TU=UF$o9=q&Xx=0|hzppg(c8a^xTv zXlAryF*K9BW90K^ye_&P?oJn5kAI1Ax>0D{uB51l&u|%*nr%7%Jpbl^NFSJf)TuBTJLaL61RCt zlAU@-h)FM@gby2UvvuF4UED;d&3nK4YSPr9)175UUNXhidm#^bKSfc-xgVVT zcT0e?2E<+-iI|)GD7P=uy$wExo4Q9Tz-UlB;0M-gicOz|0t&y;dzkus)oL`!&iKX4 z@x0PhNH%=r(`T3?u+He{=o;I1Z^pH204dmgr=D`okJR#YyK&ssNVAh$-&oAYm0ibR*12I%Hbg=rZa`5jcI#g;SbyuVv#M;t#Z#*Nb zTKz(5VSEXb_spkhb1SPph;CE%xPTzss-ORq!}_z+1?n`JCZ62YJ9*dHUG4|RJ9D&g ziv`@7c7Ox=pS)n0My*l6yyda%h#s<3d-4P!;&VY2xu&Lu>4+S0kbpPsc2@L2n;U=l zTcq+rURcL+JJW^Htb(*CNRLQU zSsOdmk3cyq@Xfe32z!tFjQn4$hE&?0J$pt%7Qc5sW$(|Q&8-2eEO1MZQL^EGTcu}w z4-6cjfIH|59> z5&YP2n(f_`6DKEUv3?`2++ZSt*6MuELAow!cvuH~j%AC7q?J`3WTY6NtOx23r$D?D zjoGRFK zOs{>=DhmXa5T=cNL6_Zw5UvY`nzDX+#G)543J?%m10aIIf6B?hM{_iKyZpK(O%O3p z!GXwx2&qtqbpH(9~`I2$;m0`w*ZHnu%`5TeYXf|&`*Y|)B$!wX!QH4 zhVsJ7?|O|=OY++oM5aK;1JVm}u&8C6lAQbp44*F)xaJ(#U*uZV%VHGkh^Ga*Gn)^q zUq)$5sEasxQ4$&#g8xBcGN8C^Zfr0TzWHS<2su#4k!NZET9k~9)1V}G*8OERz(TNI z*qB=0umXhfVmndy^~{bpFIsO>t}{ol3is!OZNJ`nw+hW5*7X zMz&q7-tET9va+uLU2_4?4)X7EyUWBB6usbskq`}}lj-Ko&{4MTb8J;fkoyMl{0wAd zAj>5!EG%RQI6!ECfK@o(LvR+Cn&!DjnI=@tI9MF&{3k`Oe|ta|k@NbAYB5kFn0arK zg???``z##|To&i`smziRRmkV|g1b!HcZ?T)reRfkP;&b8X@JK~_m=41KwSb3Ihk9c zyjn*$T~gNcmI1mU2fe`JFyIr4iTf*v8cTivF)_qH1Eo(JwPBh<&b#61+t&$W{4>T8 zE*vm|Isz*2faL4E7#D@PE4eNj;8>XkQvgJ;25xv_}sTEM`q#d0*Fl-)PH8+ zh(SZcs=_ z7O-jO4u`91^JS>eqsM~!o05-J4Jy+8{X*E+;V1C2fOd8t{fSUYUOuG4GzGl; z@^JOSEj*A;*?SzC6HQO(Upg5R7o@2*sW=B-y936C=@#e6qg)7{;b=kp^Q)tF{7`t# z13CWyCiCFn0J=du3LGZXgyap%yWTjcEEMT$!e@7&h~Y z7wlA00FQvB!32KDbjS|Q7svtK8=Hb2$^;r!PWgyrc6X<&9wk-_gapqCFVr5zcGe`5 zd-;f>sHuIh@4aD;Yk#CXkUzfjbCu-ltHLtN{Z@SwYcmG!rgo{gTTgy<3qO&wf#g)& zIAn~j7~pZA&PO$*;h;6}#m=G7V){kj_V)Fnb+1_ceA77?yFE{t82+hku%o)I&7`K4 zJZ^Bd4!D32AMrmO6}`87&taqM5%_N(U68G&jreoF z3AXVYH*RP>_PhucwYVj&^z?MwI66?Q7_x(Q8!ZbOl-6Wb&-IR-B>BYppzTmx)!)B= zBgy6KQZ7+E|8N1AneAI|lrqxL=yxTKgZJ2*Wb-)YLGatpJ!mo<7#wWFIlbd~wQme~ zyPy)*YXF8G=|`YFEULC&%TtOlF-gIBEo|~f`uh4Cu^ny_2o1NusMU?5aeZU9doS8! zm*`-OsP;QB{GRj6=k>Lss7Gmu*mQ19&KnaM!+1Y_k*mGYv4g%X8g}dVxLDK7qes$E zd%6Q>*Gv+eB^nzWg`I=_{7xSLbEIb(bUdkA?++Z8;}R5X!@=441PlOR;m+!mvZYNu z7emS5<_%nB!OyG04R(s3N?Ell3@iG`C@DJvPWhs}T7?GFR})S_ zlV3V0wr0l}=;`-TAAH)5V%7eD6a$e%t@6E}e=a&y?~DcR{l4gt0kgNQO{{SpIFCVC zCj!K0MjwJ}rB`So>qYP<`Iii#BnTLYW>>mBBkEs?_g zp+zYvcSH_m<&TSmM66ouD#F>6*lt#!wPGk-YWCeK64PN(JnELdl;?zXqsZ}55RO*zLBGYk$FfWgbi8p++~IP_g7x|YD?Uv#&$C(T0HNpJ&ujM)rD3H+~v~n0^Vm z3Ofb|NRZBr$7a?}Xm5i|t|(*>gLjTFj*dtfUsW*C@MFp5&Ui2ze3KR-WS5F~vkKKhrN zyR8j&ly&b#{Q{An*{U}*OJop@f%14V{0|3G9>KQL-)51c817qzi8yVyWVs_S8GR^y z>>&wJck8DXebJ7~ome2|CdyEYj|K(>^*|Bg1904sgN2~s;fG{kfA-Qn_88zOY^{=q z$58}%78Kw?WB6tMT((CLpULHAy4_1g%@xHn4c|glqEK3(u>&V_)e!s)<0RV!Zptd+yC&@kU`1 zn1tNZ89D4~u~Xd71D*q%HPh`O?d>h);Rd)0j#>i}mm4Uxite7>7|4gST`QD@ zxs3)sXlSYB-nv905sr)ytkU&1fcqmmUwAe=4m*zEV1Ms~ZXawLu#u2$J9Xy5j?qN$ zc_WOMKVFC7{Nl=R?y}on zNQiRXcqgAo%f{BhFyDw4gtN4{Py|2{{K#1xx3#;=fIyB<6&(!J9>f8Y8ajz(#odWk zmqalkyJ$!MjUv)KBaq5_bDu+-5c3)hjhJ~~t_u7o1aNe0K3tX-a<-e{iTmQUhnsl} z_TnM4?>s%MMMU5zRqd(`WaX)S(e6j@9Dx&M3Y-$;P(J-LpZ@vHIXK|p0)h1=AfLxz z1qeiR%*~k@F09Z>fHA|~e_V8MqHGo_Ba7d~b)R>Le1ur%EGeZlR9KKBe+XR#K){=g zua4zf2ooFvophiZts5-g19&GuS6YrCcGdj2wWe|6&Y8?bY2;Z%`Bq@V*dA&^o?qiU@aaYNjG_;ryK4#MqQqz0I#d^X-+&`T6K z(|z}5EF|jS(3L#M%w8BU6=C%t;hTN5n|RbIvR^L(=c{LFk3clA4liH5YWj<`n-dXf znO5iB2(oEX6pjB!ceJq~6f7W{jBq`W6ES1s;|vFUaH?RF@@SQEZ`{9Q&w_vce3&@+lYLJ42%U8 zz}cW`NZMyL#3LKY!9bkp)FILhX_y!FpU-0MH?;`_DWO)~>jE&0+1-sx2Mtc)21-%m zg|Bb6&(QT=tP^>cl4Adr-0|^`4=PBZ+a72-&VmV22Wt)x=|LG2iT%HWdhaplN+1$M zIe!Kp4(9kUISH}8DzTvVf5f<5eda(3h3O#$XIZ9&xA~qO{TWe{l4?#BscD_;`hS>v z6Q~;7zis$xpdHDk&_Dz33b%?%Nwbt84a$^8kp>zlk|vePSd?25ASDqPF{>ed&hw(n`PNi^gI@46m~Dmk`5)>Dy|)4LD>bKe`u zKrb%~l2u@Jl4kqEhgB^>33tP=PwggT7%I5ja+TDLjcr_aQ=@S?ZdYuqNNJqP(L0N_ z6KA^9uX&koPr2dglP4FoMrs3QnPKB&zb-kM`yzdf*!-2D0|>s0on(*^@}eqCdY8~3F?Y1fA?$Wk|M z-69>&?Q7TM^tg+!oA_TdZ0k`V2eZOk29Pr*qih$&=A2b-x)$vcLNjBB}RUU}?lsC`)X_RiDA zpVmn8ek#P=h&(PxVn~zu`g*9@xFS?SSq8`0`40?4{!*S4SmQQ({`}Qok;?3h?dSR6 z@|N`Xz3o-)uaKRks6{ z=Gyq1y}w*bU%ze+m2S!LqeS)=Rs*uhW zx(VeE>hj(MhEFnUvcM1)7r%)~mNU8{Qhx9Zocu5rb7#wC6pmNMCfxe8&!vk$!6_{i>m&EUaQ_9 z$|qu`>x4&5ZL{r9MjIDF&vugPu8Zu!6n2jG>!(pOXPhYZY)G%O-GRYCety21Jxdf& z^&raNYb2@_S9P;kvu5HYM(eql9`Ay8?ED@?t}j_Ny6or@@2gwBpPZQFlVUVu#Wlpw zM>#)^ySKR74#mM9hQ)i4oufd(T;H^Dx^Q%-r2${EnD|Sn%4yT5x3wlGytDn?YrEjD zzYggzl6EiUAk|^SH6L2rG_!O=?WB)IMA(f;Nxgt!!R5<(Br>($SG#>sAywz1{n(4U zGoP!x=^L+WWO-2{w`Ts<#b3UD-JP(cJ~A{soE!uwyO7v^g}y#}f+9auf``~Fk2$5{ z{Pw5R2Dg0i6gco6k?rs01jP-gKk&2SO*aS-&8XF4&YIdbjYw`u()wY9g&R{}pAeCnb zy`o%b(7aC_8e+~L^aT@w5>s_;(khf~cXC-RJNoQ0Dj!ZpNA8#=DQO~?$H$sD(cH^R z`4FCVo`8X+O>|Y`+=xi$_}&nmmHsaPQ9h)=(w>qwfAQi|ra}E|fi%xch;b274WhZX z?!JPxOl--$07VTA{7T;3!zWI>qnZyJ)AiTSrhAsZd>P&?(!8k4=k1j5_AKs+Lb15^ zhb68#Jy%Te1&9T`8L$0~wFjO|wph1LPb%+mu>EpT&Qe(EX{9FJtRt>#mAKEX+Wy33 z0c6LVXz*r8qh2@Kmj*H88Y$L(Bhhh(*ox8y{MrW68mjqZH`)GQRC-dX%8_%=Ns|4m<>|z(D&umV~KNk5Z8^`k*zfp6~X!IjD!Y zWmMi|={jx}Qhi&ZY#md*mNAz_tWFrLOeQgqxLdley}f;C@Wnzg1T3!T-PWz;KArZ# z_|4dD(0yli<_z_GyZ;*Wv=|+BC1*)0E?RQtmt4YB3B)3mXKN-+oaitj#nu71*oy{t zGc@7C+V9XSAOPkmecGe*y+JE@fO&Or$$ptIqaT*d5Q`NRtuz*62mM}>04EFo-kY}T z9UWy32I+~|aX#TvaeFz+)ZGIY-;{WnG11#Vm?9=l&#%{kHl!8{zL+=meZ`%tXQx)L zVt0o0hA=YG&$gETUn6o}W$a=Ub#}Wi{E$9=KH!|xr;w_SsK((%d$Q~|r=VRjq7o5R z*nL`K@FkgtRb*#*iCq{*gA%`qLg#&7Sq^F_SdE+&-@@MMMwesJ6vrms&YrYL75R^aa$_xl;goo z-FMvkThxxv6LhnR8}Af*UVl5&eZz*Es0a#I@dOvakD@2L)88ag<7dP=b8~)PuEU(9 zE%n)ZnexXzb=@r2&pT7T^u~UE=(uAC-?PgBOyJ9{cR{6T&1k+*ft^|4c7mn$WU<~# z3MW2Qcn}paQVBEi_uyu+MX*ju-9<|c)>0ev^?5HzNh#75u(w(D-52ZBT*=yhSYW$e@!_WB^vY0!xb$&{4y2phUZDBaC-I);2h;JaMR>AmWj>v{SoF))d6bR|zCs0rzz`9)bWc(ahS_Z|WD_h9jSl8@j=lM@ ztPA_zO%2;U&oNVu5qeQvTtQqc|E2}D@aQq3T45?K)s>)31MR$=0>;%T`PC z+NrNOBhTs0hB|X?0qOB_Cpb*vy!5A$Rr#jEYU%yoUL7?5d2Djr=ZBVmPe&jas8CSY za1$fwtEj(g_g3#Za^%Qt;Q;~8-qYQg-ugC5!|i^G{En0NWe#EShaDE++(qQLsOwcfE;uCTHFn7PEa6VJe zA;b86R#4w?6Z88ds*;ovejP(y&Oc64RC_f_)KC^Ggm1C|vZ;IKUW=?~6giog`$9Pt zRT3k!X4|$a?$_mG{m&?H9Ar0oFH`wso$}+m z%jR1RN8&d3883~$zwVt}cdE9iYPlE9;uo*y3wnJeDX9%W&t z&D3L>wh=DBewIWU+ST%>ALfW@bSWHpxoP-&QNyGON7t%6lTJ63f2raX1~Gl-C5(@t z$u4Us2=D#qnu_UAkSXUIFrV6Iy-hrvqrSH1?JBQP-O}E(m22pp?5kOe z)|bG{X4LWSrfni&K-IzByV_BmM#gw{dLo>a*LA6>%yTq$W^<%-OMUKw#r_S;niO|D z%>TTDcZ0O@hruW4?{6zG=G{$l8dm6}-~MbWen?O~v_Qtm(ROm7RO)j1)o)3eIYYcD z{r$B|1-~O_S4@{1tlcegA!>zm*7#$B++c0~sabq`iCDXWZ?eRfHQo{YNibkM#O_iu z47?9)HFNiu<|8Z526}%{)bM;%XM1!{*Mk~|ubU??m*!=!BzvQ-g2}eECm-Csd(u>o zm$S`c{&Ydfx?^{k;wP)n#u%p;4)ITf>4BdT)e-zSeg&xAq zn@3H9XL1lNyPw4kO@d1m_O-08{e83R>C%mcf^*jS?GxIoG%X+L8uJy8OAKoh5hpMX zw1CtBh#6+038ulO78WrmLFFjXcFn3P6a63_Fy}ylyRg=-cfS{gUmq9UKNpX9ux)KL zKX!FV9%{o|w~W^O^EbJb^gPo#| zLiImN4E>q{e=)5e%O)iZoX`K9WIJo=vG|;pxZ(!nc=K5YAeNcIFctsSOY3iLa7Nuq zvSAPmpTusubDX`7(1;RCK|^_`^dJ3VZo}F6Tg|6wHlN=ua@uV6=3D6ZOCJPy0Hg&W z<;xWw#T2+!X%5tfWMUK!4uZj~WqXgA!X4}oJ8$mkg7P(D&VwNaaidbMUiY?sz2%!c z^VO#Ln}6?acwDt~zTxjx6*JL@bMXRu6CgeT_>N^^lf>adqbnyJT&W}Yw@^QT?reOvlEgrD>7xJ`_ojFy(oe`$)5o!P4y zJkU$Q*eke|iiiHKwRXIUFQ?lB_c%E&srPP1ld~iZSX@RK=-bGMk2ff4$&ObuHGe!6 zqU8@}%ql5!H1VMmIIqIsPmc-OhmOFxA^#Am$q=bQlw2ui4uccy>O2zyF1eV|h(DDT zWE(^oBbq2icC6R}s=drOC9jkn*dC0eH3)P$U56A} zI!C{EV#d2tO6%`>x>3VHNE99&VDDW`MXf|$hqu3d+sS=)+mj`FMVtbW_ZFTz+z?;` z>L)-kv_Gd`lVcnP33Jpcly`coHaR+e_1(%Su7_F81J^2f8lJ1GTY^4!>o`}CE9@^p z@VyF&?R-2J-0_nYt#e~dE?&GSbuH^0TJJNqrT7r5^7AeX&S=I1d2;aZiGD=SVrW!gh>`W z#)@6Ghb?3L=pKWYQ084_oeci*dCdd=Sj(iEf!qu>#4P1PB`7MWTnqZu)89}0UJPHN z!5{(h2zZWvJfjs1Y~XZEj8p5Is{qr=Kt^IU%^`GC+2Q%Ii}OP zQzBU+2$ph-7MT&bn1_*^jfajUu@O`RkW73geU{S$eeK@thPMK$h6>iTu zZ|{d-D8ph)8SntL#Da`p5Yn;>5WTo1yW#-;;+wLXUf00qQupEA5777`1im# z35yDM=E>{EA1wfzX;UEY!YL}|!UaOX^10A|N=V$s-l6$|kdP3li2T21t%B^Wx78$2 z{n`m<(8Gu(8q9}p(jqcz7CB#$5d-YDa3OLF7ap(P$mAV}ICA6-P$x12fiMZv)yR|v?ZW5;!;jxR)KpBQxF|Brppld)En5SD~A1T9UX76 z;)-S-fFlDy>fknVLqfgq?9e2H)8SNFb?V-$$u$EJRYpc82E=EqDcp~JFg_#SKhj@r z+;|567Cah@F(bigR1-4n`7j9vSL7jf7cmVQf6zVHvWW@$^x>p3tQS#1uS30u=Q8I^ z@w5kpkKuiTrUwNbdLa+2&hOthfcydmp8`y!FfIZ^_qYcW zdJB(dp>?JOGDoJ*kIOWg9CUzJ!du&sx3=SIGdOKO6FV1^G0JNw0f;UD%>qL80vVYw zyu}q{Pqs84D-}e2~0@S`@Kj9Tr!Oo9el8 zhP4?ni&7BM16eEMkyXqpfD{8<`Ue-6sbYn4YPGyGAj^0`wo9QLBq(fgqQY<5B+|gJ zL@`qX1p_nB(_0-JyuX%+LNjQd)t8>GMh=O(8OAkkX|4bPtuEq`1f@dydtN(mw9Qc& z157H2&~$z{HeRRbj%CWr($cptPcHy5yt1}-R@bsq|A4;>v5M|~El$mpCroz}A__=F zVBnmBU9cpPi@gp>g{baO!GN!EBP~tU&bEDrR=4Qd1T9Uu*98d0W4~?z`c@elpNBBT z09}{%9SA!|jvxPPCZnr>{`2Szg?Fd^S_60Ii}>UC%J$-tl1i{2W<5|^dfO`FGBN(8 zX<;0+^YIzLH6Y*t+@!k!o;L1=3)(@L{H>4S?5GT2T79w|9Y3~!2Od;8ziyrrdo1gPU9;pnpGB<6*T;}S5$pjtpIAxbffVeucjnrr%ohHxp` z1m**b!zwXS_y4IumcVdnk(_$gCdcnA!3qp-H1Z6r0c>iI!439~=%k>FQza!+0V5JF zJN&CV)9=^ME1G>+X@n7mRqhzi3E?a~*ci~F^!LxEoQi~n_ygpPj*^#s7q@JqH6ok0!2AHhGv4(pI46Tru4AmGT zutS{?gK5uU=~GTRQ`~zgPytm4)q!rgBYjcvnw}uMV8rLa)sX$$noR8+rZS* z^_w=yA;iGd`o8%*#=IQ^T2z4`qARRAf(bY!C`-$i5B9Gj)5xm8k&W`gs0^7vn)zT; z{R1W-)C#vYEV#s=D3hKY&tjw=EQJyPo+zNHZ9v5UA|t%8z-V8t#;|$OTSx;QWClDC zX|XCOhGD9MvI750GD$GTK_B!9mp*@fcJyPW_e~J9ZY1%6 zHNZ=RJL03g-DtaBSN9;QZ~PW6dBwl)l82Cwbq5^{F2};t^DbTjG7e%C!!0~kbjzGC zXea|dK+7C6dJ?08{`I{kBa{cC3(j}h3Y93NA>|h|4*=#)LLCfOCp0PfT<{M?JPtA~ zud7R?`AGGnT{Kz1wcxU2Vq;hS`$aBew_$;7R8745VJASH!vux!F~gyp%)*$DZodK% z3?h*4k7qM}Z&Ql9b4QVz``@=Gav6G0umzA_NF0T*kdcvrT9TJ6?m1u5Zre6}^2tJG zIgMjD@FgJ?qWPBxd7EP^Nm*EBdaVL8fU0tG8^J|j9|6vpBFH&3K<8RZYpWR;aO5>H zJUo2!T=~bVjZL|k*uFJJNI2jb_qwMHC?Z=**^b?dEC_&+@ zgixHFDOw7w2?3GO3W6G(m%ix}2Mj)m9|ZX(>WJOmN^vk-$GxO=!J5Xy!}G6qJr?#F zTqzv*@Z9UIInxM+Jr&btB4i@*&Qnk@!NWpXi@1PKMip!o%gF<|OC;+&`n(o+~l?-@qwM9)VETYyasGApVAfo7vgc3c17gfFpXrJNr6JG6B%z5z}^+ zF$AVXmMQ2m+Q(#i;KH`TlLtnV{>ORT-Tuh<%rUZV{~j>T`4t$D&FQ+qn?`oPcr=fTt%fAjn?F&3&HG6xVH2Y` z4)vba1A*1>?ktDORR!cy+%0QFax+{S#Ll=whEZJk9ee3MQTdEE3~>z4S{d%L;M;L? zD_;F`dty;u`QOS_#eM+NxCSE7a5N1TsLkNtk8+aj5+s6N4h;#u1@wNi5iU`ipz6iO zm>|t9=*r@{9U3u_oe! z=6yw#_Wu1f2sT$38oHuN!=eZ1bxW1EUT9d6qDQEy^soapC^>!^u;aRo`V!0E2%8CV zx>FUcU$zlqzsh>O5eB$t7GyEfBhcbv} z_*hhM*CD_{M-?AGZwXcvK`3BXAdH@}7eSZ-!i4n{^co|749dnrkNK!NCK4)pz8ax1 zYQw6mq~Xl;=}91+19C8~6uys6(9P`~$~QWnWL4)a&8E>XM(YHfQUMnL-h=(4#yU6{ zLL0k>t3QrvPq@rN$BSM9%?d>_h`%5({(5DtG-L^oK$G3+vl+IP$TZtU!swh3c$n*O z4tj_^^lU4Ler7tk&k?>+pxgj>J6WSE2t;7-hcn@VyL)PK6w(cvN^j^m059V32`g+_ z6ab+-^*pGj_40-S`;@i|GsAP>)&=+TMe7eDeXWP}Gm(E6TBVzU^@is74Z2lXuOr3w zP<~)(Qhvbwzk2109H*NYK7?z$iIXCvP|F2fe}D-g%s%U4QfskNFcBu35O7ve7YJj; zVo4;OHolAhAXLE?cQsZ9c(qguW60CMM9n2b)QpU?WA8=>cJP&+IEmJtfC-q5UZhL{ zk5q(q$p0GjO)lXXkX9@Bb>t#A*8(mo*YzpCmKeQvobn4vvuoE5vIY%(ghh09B64w8oBIlAcpgO5loC; z_2F^;@= z`TF%4*c3}i72(ttHaB8~;(GGZ#vnD=XXDPDx3G;!L=M+siY)YYJ9mCrQ!Fe3ObNXz zHfT&t%v`WUknDg0s_C#tmO;hMD6W{k&{Ch(IS0HJ6yiv?(Kx)o+&mf(jMwmh=XYFpc5L zer!rw2LgG5BK_L8)V)D1!^$^A@}}M$`2o%E1)ZcKoOiSR{s*dZPn`l~C1^kN(cVoj zrv-C>%6aG(eh)o8ru*}k6- z(+XwrU_o|)-;;!+c0#3+bU-?Nd$IrlzNoz^@l_qgD=VwN;TH_F1v`4m1Vvhu#QsOJ zoPpGoX9x|1H!}JIa7$9GA8&vb0Yi@J>gsvn0iXY~tVH3=4+EXMOvN5A^ zG2ej5dyDb(43v_Nj@N=asClyS6#bybUahBK7L?oqQj!d? z$5xEs&x5l*8%6}My{B}^azXnCW;ZX{-49H}1t07Ux%2`mB#7?Sfn9)=gL81O8I@6( z?BNwPQ`7Viz9m_0-fzsdT{}C=}blP}~3%|81!gnrar`SUXhZhSfx;vP3Y2 zEmEU3AZb5zu8<+s9qJl9Vv>P!da$Ius0{QtJ9RtCiW;6$UQqx08v*B|c!%R$Hkuvu z_Xxz6=^oPUlkC;eMBt{3efRt9*L!L0^3WQX1 z?rE{OvrjrI1|2rncR&~9n9j0_M$#pC1W6Za8`ND`O<0AYAwj66^f}Kiw*)rbs4E~h zrh{?__VDd^SoL6g@${yzUtcN;01%i*Ss$q$sa0c0PLrAGw+&!3FvYQ@67trCB(MDWSYRxrRshNS z_NCeQ_pVh}9boz9`UatleWzpI)IBH5Y4c z3e^(zCN+U&GqL3Dl%O^Kx9lz{$;$ks2*}Svud=8p0tM#SMH7n&8G33cKgi%uzF|o6 z@s5264IeNQL5RYkSeT#1dFT}ZEcuUxKf{2p)E;I?$i%WNUQHCz*jMD&3+W0e@C6F$ z->FIGwR(ZIkEa6vglrt5a;XUM0Oomg?M^A=a$?u8D6Ryi7HHi`gtLx=FPWlJ zr-50~T%09{;j{i&S#vjlZZgYH4M_x*1Nt4R3s808`9YcTS3J{?c^S{qyAl#JWrP ztv{J|+V1%f!`*!J=%2A~w`S$aGW1$3&Qdm_#0blsR&?9gY-XICTZUSRHe1nToEK^1 z_hSX87)sKEAAzl}QE+cakUM1~AfmVxn3J65>@%_kn<+_43U$9B-MKsqNc3cQ|6^z8 znP9YX<-cHUbZHPIU=ovmRv%D96~|T$t0;B?z!L~~xpZUm5CN&2;*RA82#1~YhQbLo zXxOZOGI6|#os-kb+>s9VKWzXgoJUTakYNdd*{j%#Rs=KMw`h|8AoGZd+S&=%`>UYT zZOi>VlnVimkqGA-+h<WzU{Ib;5??wdba}FwLF0SyRy8?mR%*PLaP* zbPa;%c^jRPJmJ7nY_#)GcOH{63TnNq)1^)atbou#>SSPlKv63C+m;Rq8Gx zN*R!w9~m%&egU>w1WRGEPG)r|HgS#lJ=&izw_gsn_%`#u=~JS{kn$<`T^$Bl0Owh) zhyMZ+IT&cvHAP1|#5uq;nuJ;pp+PjJYJ?4o@7?I05qPMoC!&Z{5F5+j7TI=TaEaOZ z;M?9X;5=MIaVGGZhDJjda$M5iV(bKjE0#@Lff=pBt)X;I2tcOTMVP_yeC|CS z8R-gMJWc=1^)cuV(s@3p+ijOA7u5d-RDlyG1j*wM+h83K6#z=Y5?U&@f#PCfJwtWB zZOD0RCg&Py(70g1Q7Iz=#c^Pl6qBWZjSJ`yXpkHlXBf*M7>(h|T7loeWT0lvXfkH% zOi6ILZnqkYL^0{-=gu=+41W|1(467HN1NAP1Qn9m-o1TS{#lOrOGN+z7G{>bld;TA zSq&47W{m6dv<3i8!>dm|jgwGZI70!Ahiicm0_~61y9gDimnuIPL@@CXh`GJu^|N z!wU%R`K+l33W|@hH86)~hw@`4b6(3oPKq(g#3-W;cn}qg*=xb|bV3s2%EqzeR=rXVvn4bRo zo`v5pe}(Gg-}`NbP&4*Uvq2$&X(aA9o+jpSe~sOgt{02co#Y9o^3DG9=5nEz!mybr zZrH8U*VlK#^5V6h{h#lot!;~j1@Cl5-WvK%ZG0MmVHY2 z?8=T{I000R9lFXV+vd;R&HG}v&uq_99D{^0EI&8rg?_s!t^t(88m(Bt#dKwR%*Hr^ z%*Ftv_=EFBhngasfvts;9vNo9<`4OZJs<0yZ1S<=7T{{p-p`F;aE5I!rYtWy_TorY z&SJ4b6^KF%C-+4Io_fDiCXf6tkWA)`-IDrc*z6F<2Vp>R8s|&?v*L46?XeEQKtcEeY&4WXEyz_MR?Y%wTjVK9zHx>x(zSG6pO3g0Ywtw zPc-9+h+vT+CEV{zWQqL6ac1D$YnC50=dvajDsd(Uu(K;@cGxdvyGZ>BefHRz4cdPU z1O@n!kV_vbO%Q7Mo5WBmx`IdfXGxYgdvyJFf5h%t^Dh^m^Hs>r`9j0L19#s)r8zf< z-(z$BbSbXQ+xR26x3cc(?{Iohc-%8ZEO}SQlN+PW%hoIP-kh3PQE~s8(=wIBl*AKj zH(fE~J^2^!O1&j|dQ(}vQw7-fIy3tF!*%8@j63iu`-SzV)En}TtK;{)-hbh~M#7#8 z-5STKf<_ut@$GTKzBQ8@A>|HmwF%rz5ZBX-iKthC|i69r%VLxX7uQ$GC&U?*RP4NE(m`B-H>Q z{T=Jif>wwd!01TvGG6=k(cA#nXO8(Ho%Neq*Nku70!6Qd7Ux?B%|*{ggGpQnAR(GF zZv4Ij;E&cwk2x^V`Lh^?TbijKLYI<+w?_Gk^B3kTD_7p^!|{klC}EQ?bK#-{=JPNT z^#Fm8+TS2M5f+L&n#v!_Fm_#Cn1g790*}LF3g-#UU4^RcXMcZxi$As27|~v{!fEQE zOwedcN5^_{3X#yffyauOgU^?UE4Z_G-GXVzCU|J|#x%FGiZ|R9NKa?N zglj7~@53abPNW$*tpWJDTj=YD8t&|`vJFf@4l_N7J2-p%X)Z>=6RjzrewWeVUo>z6 zh*aZypt!jBI!3JcKFp50)g81RiL?b+3xpj13Hw;L4i_ zB>OtV5}-_&d3fA0h?MBq!1Ed|9xM9_ZHa+iWdO)3UDRC@4STe<;-ysg5Si!+?(LSC9E;F znjXWv0F@895UKbLcszUlTzy0pOO$-TCWwz+-z=I*5%?51nq_cY>?-0~atfT{wqX4W zV{N+y>*DKc(-asr9`Tt-UV>Kktc@(sOI(bK86!5$THDW$+qI~3STws?z$Ym%B$-`6G ztHt!V$fC=2#S&^BI#}?+v&Sw@))nJufU{WPG=;*YCRjTndSXg_wTlxcm@HiY&Hxs@ z@jL<49105?ZK*@|PgDzGJUF*7GXpLriFS8W6J%AUn3fbq5xZiJE(BX`=i7_hDblOtU; z7dWDlv@nymoq7YDR!M0!>~CR&qSGuC5QsDkeh|Fq2RjQt6gTkm|K2~*F2WC1Hh$<{ z;|C#?{`3F!KmG5$@c*Sd$t}Ht?hunRF9@rT@i^a{5J;z&3MznieUse$Yy;1oJ?rdL zePZU)%dlBFwwjxBJ3S87*V|1JUHr76Nl#C2a3sy(ox&G}NGKV?q??(dC(=F>?j(jW1$mrYqGm+e>sDz3G4Rd=>KL67dRo z;-g{NFU_)o8^s|$&RVE{f#4*^%eWntr`P;HUw#sY_j6XS0=nenMGnu0TXNxuvG~C& zgcAsvs{g9qf)m=oL7IPJ?2F%m^C>)dpImRx0)hGg1_Nhyb|R~>LV1pjeRh4K&+?W= zP>CqSVZH&LEw=h!^6&hflTe23($ZeY1U?L71M8Ko&9Oxj@o5mw8wDn{hjTcfGg#aq?a0E94bvZTB zco|*|!eaB?<29?IW$3(K&?zMLyMZ@Kqj{7{WKfQqRv7k!Ur5FY>>ScVBGYQ@)<*wK z^jV;>2>$!OW#BemLahzu`U)&|R9oHGI?}+3aB-oE2}^~*v)i|CbJd2?H;-2ij^xP(3Z!5D>=_RNe;!=E(yV25-H&Ok$3?GBsdc5?n<%qAL1F)q=wo6d|9{N ze+pVk?Ow*ri(9bDEA@By1#pdKwcYAU67wo2q(UYQ%US1iK_aXUI}pa{qM`8haxDH zn6AjISt&mlJazhYVtgW}&6mo%e=ZftUscivRULs9NT`%u@C2@TuvraOP;iq676|wC z4~Nute_2VzFsWijM}~Tv&e#HFDqScZ4tOXNb}Aa9j(z6#BhL%Mp;~c8c0+Zrr+C*| zFo;lGYHG#&wwUwY)t@3)Dy7!ImxxWJl5yLIFsUE4VNOgd* zz!~BSfgzt-TL@x0kvs6YgP)Ho^k8V%b&;D_FLnn`d!&=FFKB$&C-^mpSqKAh%&zD~ z4+4J&qzxp^$ET7;8lS3h`{wBn4qb<4*qCDF!E*sjgU0FADto_eA`L-)D8H8Z41@;Y zIaMfkNjHR2q-O8+RJ9@5IB*>6YXQ~+02OJ$KMK> zXj~#{FRBPIkdnC?WM~ZoEky${SfUkv=uqnuKFP}L{!cei$a z*ka>GRj2ByVq!PQUM5Wot|MsZYGTaT_2(Ld02ho5nEb|wP-P;VM! z6pJ71!h{7bHHWJ!SLo;j{W+JOwytbsA#DM;bJ30j*x;PGqcC=n1L3P!9x;T~g&6QQr1Mb^iY(H@3FE&n;ud>swbEWPs2F3wlo%tMWcvHl+GxNxrS=#ECqaj300RC9c3-^b?Y$sP`7hW23pnw zf1>^{gMscoson5+B03NdPVuO^2b=!(?RvsT1{?`~3kJ+(jAAdEB^tD%*W>ByD670~ z-b*KfU>=af?Uvz)xMGO#YAk;JjB2R10xlQdb@pU4_bF4SUWTTt6>R^o15?qXX&(qo zVrkfdqyyOcsnC_`uI}y%>}PU)+pQDePHSzTA-vYbMt&a=+mSjZ744Ho6Nczm|vdDih&7C@VGhb1< zXCu92Xy?AsgguFT?_nP(C%|U?I1?Na(p$6V^^edrNf>vv{FDzt(AkKY(xDM046n%b zA=As{AeKxE-Z!~@qxRp}+GzB=THQezm4gpT{-`LZOoOoE+HxjG7o4riIguLqTRsLT z=O_5K&08+?GVynq;4E_9`$s~>%1~D-bPA9FVz#u{Gz38olzFTAX(+!?4^+M8MI&S} z12d7Af4Q$)IQ=M16sOEFFfAMDA*(&4F8R&73)RmNvRpA^h`5&{FaIN25B<¾q8|{@x1yCdLS19 z2A#z=3&yE=UZxC%Q>lxtx0eq!`GO^9FY z6Y^}U=l*^}_eaQBnBLO3&3JPi&gk$F-;Pmc=mp&NY#f1Re0B(MLQI;OjK*+R0gX&5 zBy2SCN9CMJwEM}i0GNfTi1BW0VYs}W4OWC|%s5iBFZPpPcWJfPJ69={D}vtZ%v7bx{G;D=Y#G32E9!64#c zVo@a}mwNUse~Re=OrzT|ct-mRI_J49UdaM1mZ^_VItpH8q)C*E&z-xMLBK^i$iYU* z-z%3t<*$l`8Z|lPH53wuiQuAA04T%`SW|=sJIzpIEf$US7T3+3m`U!deie95Kf^2dG9etTSKG9*(81$1h#OQ1O}(J zOJecH1ab2uqjHcwDgP%|b^v%Z@|XMxE}>deO6puxb1tZX20`$t&5hEY*9ilQYp5;Ah!35@(1>QO9Z)DU>^f}9^NW2`z}2976LqxU-?8~mdnAysRE%3^ zdjJ9>-*J@cp68OkX%_-kK(xoWegig*jLC(a>Ji6~&@r;WPRLfNA5*wB8&hq1V`cq8IwA2U%@JqK+BH~xMcjL{jg6brFAQpukDWRT6dwo2ts#69 zESti3aX?}Op3w{(y}?;6RoY*uenfrOfbE$YE*bE?=iFJ$1pQ$SM`yDbD);5&*5VD` z0BNEKRWT_SU&%V%QoewHDDJdm8yjd1O5N@oiGG`{ICAYCMuhpVxz(J8!{) zVy{>r^D4@!IJPGWtSh^=w4uSlo`!JAw#dNYM8iXoTf|r4I>_;|_25bb5pNu(BWAf5 zG^wQKbUdXB`gj7?Bo4SKD=W9qXddi>wF%+|kLz%DaIGmjLnUUoICuCcAlNT=tt&8T ze2BBOvT+t@m;@7Gi@7A)GN%|3kHn*oKVDP7ex_9WIL!!RLpy_OzA79%bs zDyy>}`(Vdwi}{_+dP&UwY31+@KX>e_d5;eb+Iv=vrF!A=xz?!{Vq(5{R8`Qgh`n!y z++z^sLiYE;Y)s)Xyb-tgR99EmkfDN_0rD|7m&fsZ+M&l2c*l#abrgpQ>P)KK zv+il3k8(rHY*_qm>)lv&RZ^az=F4Bu{u#SJ?fkKHZEhZ(S>KO9Q7=%CTZL*A7H6*= za`<*v!cy(l&5fyIHlNDxp-w`39@|g{`T`L)v+l{G{C9ErZob1Wx!qN7`EnKX2L;8F zOLsqQa97n_0YMEY&AWVlfp!A?Q*bexm0gP^338Hy&oA&`_V?a-Dr+3C*jrgv9`?^! z27GAu%%Rw2kUr45Z+H(}0dz_dFN)1`SEoea@PU9>q#TxI*qJpWms_?EZsGHv3)8o^zyh9uf=mK+V z!~JXU%p-aA5>bBxP5An@$pO@0l?OBZ?>T;5RfCw+a#u3HegxVms{G~4nGIYVD zg&=ANysp^(HEDyD)wj3Scid{L4yNA~&F25Ob4kKdRf?>ZmM%^oy1Kdo!Znnd!_p?T zHQw;|{^FzRTL+ZqXC_ywTQY_ppg-~i*vhc`Y@t!8>i?3CvBZ;s!@qf;Fw{_^A_)!)vF9VE37?a{6JpJM#!jMYphhMF!s2TETkjVb9bUMh(ac( zqtAjKl~`qzCU9S<%vUUNsJ-ZiTTe|o%0rX4hwzV`i`r8?`cXV}XrRL_~P_WDE=pa8+x~u@B#C^c%Tid51`1p(ol6B+UJCYowm)EcVS86kV(jg0i5> z9nG_6WzT=#yQkj^W3~wb0yCp@ob-{d;n+a|c>csLGjxHNW_2GqV1PvhVyA%hL=2U0 zATXbCPdIs?Ct}JR4EdV(T6@)|%&K_zE(r(VaA}@EI3Q~h`MEYh@`*MQtiPOrMQH7D zFj=)~(Suv1j*auqM4w&yedf|nrSakhku#W2Ph1}QmWu1$pLAefZ4R#cxP<0M*%O7p zv#F9UyJsMIB6G--hg&+{D<6@mLiQ#6O3FQEJOleEVgI0-DMtE}6qd2w@mZ*|EQIsC zU$XZNmE;*Mvj-F+U#F$i)U==@7VH2K3H?H+k#pD2pvv}`BF)|^1=Ls6W-q>?&2O2f zD4zmHssc6Tn%>>E#rR>$=~eo=7DscHfeNlgA<^~ogx`I~q~aYAOg}#{Yt11pEjeXn z3qsDSYE%K%3Md>v51Br^EAs45qOKbp6KQx`=zyvmqdchH+|_T|e9!7OHt+WZ^mq|) zX`I-&?vsWRKiW=aqNG&;l2A}QW7;&&sHNp-0R*(0cDlIizGiQ3ZN00FznOfc(MHUl z)U^mblCs9-#8Sr!5RGeH0tqbg5xamGN~o6n`OFta`_bdI!DF|p?fO-T{a>am58FJ zkjWy9n5%BSoGT}{l6v3k$zhoGdi-i}$=Qlt0#+;?L6Xgmua5&!`k{%#74T%}l!G^w zq0Nq|OK)%OYjA`lY)$S&rS2}{Q-C1!0Sw+%k#{v@bgh*r2~pfU2C%Qh%a;TBfX(1fma`(Vxc zbk9T*4y@p|ff~$&Kx8`QrlR&~tqMD?_BI|4nbH%($m)$|#ZD;#wBVYb<=Eo|-R>FN zfX!$=Lo7SNX;D_*{;Z#DkmyJXXP?Y@Y*x7m(hO-$T93BEQmUtDPNc}_-uzi}F_}V1 zkQ9FT(TANN4XN>+;m1IMjHi21QN>LNITds6+)Z?@;b+>xXE!!J(Hd4(hl6;XaIeJ{ zZ(~iH=yMX?0cj`zV43O!Wz35OGw>!Hhu$sh??(R@CUK+oqwz|BzPJ%r(B&n&)u99w zm>jTsIpW5Jz|sA%LOQT>07p0zrcc*hAXHvg_VJ^Oy3@YBd*>sl_5_eN0GQ)q6P*$w-nyFdhJj^69W`u+!GVm%V>~}h1 zFMf$nWx{BWY}%(z@OX(&og`U?Q-X|%Urbsfpoi$zKlW^yi=jJ)jYbMtUBRuH)^LFU zm`vDrQ*-mHzk#F#`QFyhF`nfw8!GRW2?A9fX)o4j>uZfL~WJFWBX~ z1tl!OsD#QR%K$eiDcw^b?!FUr7>V-O{C)13gL_KF04g`si69yjN;G4zBDQq*6)4S! z;t>5(Y3%|?!9w!SVBSquK0R5b3qDi9kGISdKe)Y zBadI($|yL*xtE^54!a_tAl(tWYVSIPJHCoG`(!1HkhPX|W;H&V^CT^_|-=zz#s5gbR&-9r#el3wmcc6RN;v{Wz^;esa< zV%ZCywJJEqreXkjX4Du<BE#K`9RT~U9gf)T!T%mTyQ9jGgYwUlspf4GOez;#| z`u5(acB_NoyuC}CwEH`1PSJd0tSwPimxA2^Pc}Fr>HUS$fgdw!I<;q+|I>MSX9+U} z*M72-YBM_6`BtBo@TSbk?rq(YNh05k$h?15>EnTW?SB7+8wHV58FOmxT#d`x#8w{}i9_rNL| zM~)<6Ou9Dr_ef{$-nn0sl4P>sEs0dc%a>Tw+@KGbbabTdw>1vZm~{H{)!5ii#i&uq z0|x~&GEP^1jc!u^wO!9om5~KTz}IeND|Ra06N~ayCBi^XZ#sH)O8FLc`#( z0&|yi8UcSNm;mfCYnlK8YxMsaeB=oMVn|LI);#0{Ovn|P7?S(_`#bg))9Vw_r;;`T zNNJH<+K|;UY20=M!16d1S7K77eawL{6JM5;q#WCzIdigej0t)Iz6ufR>s@>wUUU{NbRq`(q4AP|^e?wZ5IY?yhkNdjQ64bd)2e`XuQ9s0}r|oB2l6 z^@KaRxz&MCRqHquzn%|C0i6Fz3@tSsC!7EqADO84@zx37R77TGlYeEW>hyDyWfDjNq~pO5>?fqr#$>h9mS}TF-$72pUdX{ z?g|MaiLWkg$Kf^EZgP8=?>jK487y@VaB%v7m=RbOmd?irXe6Dde)zwmDE&9=rT-KE z6r?cmB8w?}@aPc@>cal%XluL7aHW%0wV~bOz=37s;9T(39i`IVBb?seZ!##SxTODo z@#+32THpUnf6EbKZIOdA0L1pC3#YI0j^Uv{55%hkZ~u$d!6tv%340{Iay`rLS_=ge28!(%{-k!!zV}9gkO9)SpqUu6HF70y;{p zF&?^&2din9ptSdC#tY~eNVfl8<@<9*+C#|#Q)6xiX7a{O>3WTyQ&@sjxhXjp%lLJo z_U4*o(mwIe;I&OJlY8tpQ>|8o9QI5!I!1m?=i0-Q<5ZC1;AV4YL9qWq^;+`Fug!mF z!qx3rmz6=!_(evA(41<+1rToVO8A_&>G@gjGXrrc8yv>ZAkm3&Q}zlq`b}Pyy7zhf zn|#pWjh64xyWPZMB6xz`#F)HNYIDE&YHqg@hmsk$9jbzaL zO(ynw8?@_*8}&x4*}0YKE6J%JJ-(n*omx!$0I_F#XHJk|kum!@t~T}3rogZ<>)KkQ zv*cBqNG)C}2%oEc_pM+Ug+M_Ot*E5bRPHf;4mzSS>BJNk) z6EJ+^l!8X%&jEV3gbeCW0HNvpqXuH1m>J*5*hnVe$`7kn9px<&+7PO9Q(R2lcy?kz z@at$jC2|G%%1sY<8{f+Ke0bigtAwY%uI>bP#EQQQ^a=KgYXiJHD#)Mc?AF(Os9_Um zxNiv~?U~cnF&e8J+5J72B^QJr{Fe)VHlMbLsjgPAUBW2E-`X9Q}R&?b&Sp%%NuU4WTRBe@!k6UGZ&qE;+*L=1!pS=F?~~*256;T97l@Z`6{;_Ig`34hhbgX=`g+*K(9)W@cU*V;Wwovs^Gip&frhHyj># zO>U33e&Z03aeuTO_)vH{B-meZ?O{g}`My#iufvU9_?llvMwCQo@(9jd$vC`&HZ`P# ze8u|}@!BmmbMl(I;G9~cnUJ}HHTh(zJG0m3^%_^-+ook`Bn78E)aNnW=( zbVX+-Jc9=nsi`tk@_t7hZ>`4F?`UhZ_Flf=1E50{l)FM6-M@b`-*A7Jw1t>QgT-Wf(o z8&m$JjrXpz7?miXCQAk_@b&Mrr%gMy{)Iiydo}ibf1|s8ZqwqY@qdnccQ${yyShMd zZ*RJacqVNS)H0UqJb#&<-jyF`NvR(a{wz_o`yu&!>KZMftusa6v{mz{$$sxTgdZo0 zlHY443S2v+GO!~gvtBgF^yTDxuWDY}?^En_>XU}ftTUrbv}u$J+0)?SM$X|XM`98T zlB7R>_z)}5@1MaqO2*Uwo}BRgB7AMR_5x3eoW|6W#ZM^@4j$V$bVNl?;}b$Wp<{Oi zmlu+CuckY^@4o@y_Gg(AVmCU(6=g!YjP>H*#dZ z1yvu9;NgmH+KIJoVArjoAT}~_SakkY(sq2iLk`;76~6ti1%kz^Xs3o<+p=#%2Ft&1 z?WS$@+lGREJHY@M!K8!E&W8qm5`45TkYg0;IRhB*OKZB5w^_-bs#!?g8uI6fRfAy% z`M*KuXJuA z7eS9B|6)N&Sj2sgT!bh)eyDdLUyXnIE4-o5E~NbahL{XZck-HlLCjHp+MR|OfbxkS zaKy>g(Q&~KVOZnm|L>O!X;A@T8bT*I4YVf5QR3_mxDh-zADTfVjIVg9wqj8fJXp@?9-~+G&D&RJx~B5 zjvhqj7}Y3IDut>*r-ng25(YvDB?^R1lC~h>G*MT76)~%yQhyg&H_;?TNw*PQSI*sx zwC5f#hJ1+T$7X4{@z0SF@0Ubl0Yc*Uzk$IGqYOyLlV>6I5!DcAP|4p1)*#eY^Xmvx zkUHVXkfI=jfS_Jgsi! zf#Lb_$|deL z-G{7|rbOIjsduLpHr$kPiX`6v6zu?RJD7oXQFiq}U7)cHn=eKn%LxJ-Aa=M>zn&pN zAq;d>MI@{wL8_Q|{%UzNo+_$s=#-P;fy2BZ9dE6!CW&Fpfzr|yRxy_Bd;8kH5d^^T za(07zppvQKPssZ1kcL!tAHZM2VVA+aC3RpT52kR+zd?hJ!e0Cif3g~FJK&|R@k$Uq zAm}m{kKGy~RV+2y5>^{Wi`vlLU0U5D6Vp(6{QWNS*zM&KnHgz!tyv761@X;}_*0jZ8xzx--m zvPvlxT2P=ElSN12$@*A*^nilvL0#c*P*5kX3KFmt;iY|{%@34#D#4c3j3<2!g0aNP zq%00+?Uqd!slF&Sp>6U26%6KozfMABOatm)iFyPBOw5!Mbicl%?JfStZlHMp*|5Mc zUNcM2>!jQQg!jK|iC58GcZIM)iGG8Z*ACmo_w*Z~Nl9S?{7Q$&ML&H0bMwDvWKsj= zFAOIyKl~}|Nh@UhV~+0usK+jjP3Z?n0b|q{*_cR$1vP4XINRcl7x>`IB(Ot~t4GrO z@9HhyUc6J40jdDIW~`gS2GT8l>fW<=liuQUl+Xi^JxO0gUGqK`oT=Z)IzK)jA2?}G ztD{rOa{COP7%`)?Il@butf$=0&D*%_(a~ujF5D2y`8QlsKG^LBP1o-NyM?eyi5@oy zos10r8hfz&`s~cS{5BJsIm8x)Xr!>x#&Ng`5@Rng{fP%i|1#P}&Eu5+1CsE}Fi8>S2pR&b? zmJDGZ3}axJ3`*fMfAUKnpd*GSM~<$M|58)curL|fE~1=G%shy!qwe~pk)61oyL~DY&pu#r6UZXMSSH{np=Az6)W3^+49#$WDK7C2-v?uU9Jbeh zkA_Gst`H$8UJ-eO;RGB;G_xoeJv-(ls4c$Cq`U6Tn}ewI|Gx{1+%Jblc_JacJbemf z6pSAEUBhNnp)i1q0he#Y$KN}7Vc_udA2*$`GH`sUv)A6i;TT@SG5Bx9`M;q6C zF6cq6lDlOs?K+~ND-bVHb7N~$&?=RCAZ`46-kmC}dcr8oQW-P#0K!Rz?;hD`7B4l`nPT(9gu;ZHo9M-8kNwD zLMUlyV(AA%Pl!UNRsanEF)%@SrMi$FlZ957Aail?sZ*9|Eo0M1G+@0j)8aW+CqMRY zctwN59jH8&T7oE$Zb6BRas zqxXEX#_ZpqG==xy4$}m6h;U=#ipPbDAJJwrB#+KLfq(_g2*$ubWbsBb!BQ^sr>6QZ-haV|#N(N5e237|96)!z0g(28)8z6S4P@6sp;)*$ zxli%cI_AOZMUNWBY-ZsWLYt78ng7Nw>GI%m%;i5ghIPe{L!%Fhy{E$K; z&hcm(J6+g9nvxn zhGn!32Uc+By5M&+^m6hi05I39%1`jo=Ji|jy|XZ6y#Dp4>SSB`4!6&&HOV4Ug>;WY z8q_<=&M9poql&{uiuOF=wAYrAk^kD(o(&m(Cuv(GZ&Ra8Y<%`pZ z*=?vT0^cKBG!b6!#>oZRlt>t*1x5$Zfn{O{ST(KT(PSjL<|wEe%sC-;#Oaj*fG0}axK~X)ZR+cLz?c&= zfYy57Of=XS=rsrj9GcfVOoVh>>vf@kjK@T1PiWL=tc(E& zj8H8`|IP)|Yl@wAb^X06jGm6V4`(+aW(87YO4@S>hpGgA(UM;Khnt|@LPA16h?x@g zcmTVh@vM~qy2PXxj3s6PT_2T{`4OH4BXlBU{wVHBy9&_( zV&4leC=tnVwpofj6|_`wPFA9G%t#v;3OcaTK)eU@mh}N-UkDWF#vAQ(zI8Q2g%optRw^I*g{JJ>HOp2L8MKw%{|#(d~b&-rU2UBMym58QBEErAI_N~5=MN0 zSxsF^wIv~cIXPX>FpgnMk)niXz){p!D5ZYgfeK~FIbn`5G0-DycKf9(1DFQlFXX4t zbqG`Qr@XROLG=Si5>)8#t)IR^KUHXpOQbY~?WPd(#M8KBL7LLqxygvz# z^``SfTv4sBk_7`Xc6GRZg@^C5t^>1n4N$#20ys<4EXvra9 zXS+WW$N>pCZzrUaUQGIZsk|4I>HB@iHxqunf5F?4?rb~OXif8_Xu&D7|j9sDSy<$-9VL5abQF$KLsDvXqTCaYvd z9D&&7%Qjp93>+u%8jeU-8!p=8IkXsM*jk#!XCKa&aJ@SLMLrZA??J8zK_)Vg<#t?x zAkadP3LBJ(wKY!wZK}^7hGg4XNh@8d?Py~AtnhE1&28A502De7YZ@W}c{_e7J{)(C zs|G`-vw@?O<4CnA9q)1I`T7uH98^H4<ii5^WgKd6N%_v!qW*{d}fDB5c;cwG%XGjlw^cyV;81Ph{v9uvg*NAO$Mr4As9tX zxs81js*^~JbCIo3>@Owg3L{e43_K6o|5s|hxdw=xS7oE8E@bL=YZS~rPyQ>WM~%5ta$ARXnHYHc(Kj%Xeded@ekF7v1e_n5f_u zH4-$S;)4Dy)bT(F;3fCj!JbgNy8fgFYXJy%H1SbeDoe=t2NQ#;-Z8efLeOGunVA^4 zjtvrdlvd&0tG1k&duV1iCM%yW(84C|KWT1!>H78|=e>t#E|{CtY~S(7I!!0}dPv{P z{ukuz$ZN&q$5AnkF`$+^km~|n30pNWjl&j>>q4xCFs-g5jv zb=gVr!s*0Zhy7JjhaL2`Ue7vyNB585^vt9fM?9~%CL{<}TYB|eXJiuwZqC@rNkm;2 zNGy7YnZh#>-c0cgWn$p2rxN-UoJuRwF=cs+;|HtU>#goQxziq(HR@=-`m{>hniY92 z39{}7+P3VvHdL!3#=)zk8G<4ViTgC;XXhtN%!t^UZnPS2s`B|i_W<$0>4TgzSo(l` zp<^B?`e0+h1~__@1<$rz&iT1^)s=R`;{)vO-Su%*KjyzKT(NytmHZ_mcywS*5@+p0K)qhMd3~=EkD3hrv1+wgT&u|J~ zPI_Y|<~edmNcO8ZzAUuLr$M#C{&bc3hs{n6tC_SSYg8Ne6@=}<_66vj5atISG5Fj1 z)FwerRv4C;-~)-cI8+Cj9at95kjfF3NyMooj}K8!tUrKfwDq*c^T0OS5T7GSmgT>> zTM~rN{<^i-a`Zx>l6>W0by99hqTw@*KZAv%D>fOQnq{>WxV>FoeoSpf>iEf%PWu+t zOF@qpXAqKakQua=-~DOT;An!gks-hzNHtAfwd^%zr3XuVoc`2U<{i3k_CzerBO$vg zS_EU@XIhXKYujt{l58|I=6(%=f z!rOCZCQQ}kW?rv4;F+Z>m+#~BDVpOulzE89ctV|H86^lCxAIu649m!truCkf;h3BV zl88Ela7?&irW%ULMD&ZuHQU<KJTFh#&{5erdY&P}KYv5rHfsLN%lu z`5krF&!X$1wOPkkoz~M__VFkD+=HB>g~SXZzd9CfJ{f)f&k3?h?G5%Hb=Q2QQ!J)2 z^(n7ctgwgvj)eDqT=4p}+L{~UumGaJWMctvjIXSb_c(~FO7NKYXqH8E7R$N`ISm>I z6#fV;EiEE8Gwq{-6)1B^VU0Yrk8ti_$q~UAtx|Qqh~35TC{-QL%@z~N73{e%dgb98 zKIgsR8<;NlB+uuOdb&UKO$?Zmwj$8(MHHz)t>WVBkXgY|7T>Ly zXK>`Ab&PDCz-7h13=3wVwePmKN;_XSd}i_cxomE)T+QIS*ueQo7XGH?r;J#4j2?wp_u%N>dg#d>gp}BI!K)&&;mrIDq%(mM zE{GAuq#oQY4M7oH3*=>u5p)TYNn~_%H0kZiqKvCUU(XNZ>E5{f;<|ioZb67b3HzF5tK&zcYOE2r8p^}B-c)Ey3-8*<5^?Lt=F6vV#PSzr zoix*E^_0#Yc|0$su;X_0uZ8;!FY8BH4K3tQp#ZM_+Qris8{idSnXJkw1kQpdiuy9Q zRdy3;On|BHVhRhemS-1m^Uc238z?uw;yGuexbu5-5W-J%xRu_5iI?qf@^+WdZh{uu8)?f7DY*H*GCb(BBy3A$Jy ze5wlH0(TFr^G2l70L~}y-Y$o`ED1#(cs5o8CAs_ zN6+NMoG`^U(r+@;q!-E2>UcmL+w$sx-`52E(zb*bUejQSoZOejYi7&3tu?0m=7s8^ z2Xp^}1$fbT!^hy^f7g5KJva2)o~|)}GX8R-j<)w2&hI-63eJg}X2Z)u0>=@6hy)}a z7$yzi9$~OTB8_;uF%+`?ix)xvEAdl}%EZDlWqKLJHQ;Szyys8tj%(Xi)c@JWnqZk{ zUw<W_Hm9FJut z&Mz;eO~f@mCMG*ZdoXN3HaNxmbc$8l2O&Q(=eL3i$7|=kNtFqh3tTn>fiM*uJSudX-w(7ahZ*H``qfPZEp1qbD1NG>Rf9tVh?oZ z*mCXspUvcCz6PJLPCSNtSKDiBhYHvl7Qcu|+aB;Dl_|yDj@dvyUZDo)LVS zD?j``DY;KW=P&sqwB;{QALst#`M{##|$nu!eIWF3|T~6KihW%?BBo ze`CGhbh&rSRoUzD#@6(Q;G{D5B(WFM+~}>=`kRM*YJYyr>Nz9Bq-a5uvVqiQ(`4NN zG%HCfK??w^lv;VGEj>Y(ls%vxK^)1Lf_!`fG&u7Z((i76w!pN$nGy4LA4|)#-v49I zdtqOH;zsK&F{U||h?MAq-AWVp6Um|eF!qh}_5BNL%$uq+?d1>6>bzZxg*7JY+r27# zYxzYehV(7Bo?=iBZn!L2d=JQes%At&Qql*^V&dU|xq%%|qfiqiFGyd%hdW*O*y9)_ ztSNDh_nJdmddWU!f0De|9@~c5#@o9&)g(9Zn!Q;Udob_Nv)V%m8^u_r->w-SExK3Z zeWbuq?D20L=X1rYt8dgKm99L|BqpVjnzwO5lR9-3IXo$ZYsOFcs3^~kH%0iAKf?MY zwFLx{Mpjmv0xU?U0(!O1;HhwJ+$co0-D`fK`>gt!g{byC zL*aiXuV;;}HE&XuZna?1XBF>0vde$DZGCc9_m5?<&xeg#PyeWTq(E_4dhSL0waLE2 zi~*|(`!f@vNu*A-b%$XKXbQ=^ovBkLXzmfYQ%vj)D^(^XLTY-9!CN4S2;y=wVKOnu zf1cEw_0AvMu|nG1lFch#*f}u!n1lP;XVsRcFRtF36D?b~C$u#a0ifK-RFm`xx5@*) zFO3hEq?bQejgh@`&U=$$pn<1rOHMbp(jMxRKd`$bbBYO{v@3wb|3HU&TigiA*APO3 zkdCsrN`M6eswBW?p%!;9Kkim1;s>w!XsaupFGcg5Z)6|qVe=~z*3Naw`>$tTTW!c{A5@xMWw`s8uGij z`>qMxRS%WjJAaBRwDzHSu2bCsjp+&ZmbU3O{r{NzS(t?DPY$wWaev^kR`2%reV35rLFpI=jT1Dj{q-#w1$%A4O#p}7lY&$OJTq?d~|EwnY%a-%M&$qu_Ci3oh zXLP=X z`03iIlL*n!*{ZrTdJbzUvhvY(g4A6|uLXqc4upH`<<6&@Z6BLga&`2@&~m<FxP{ZeiV(&No`G|J%aKp8P1c-xr%T za|RoHGRC9&TD(a3Noj#r`}Q+ee)$FP4)YN^xN9-%>sH0VqFQ-jc8oC~ig=NuY$$+s z4bmg6<&qk(bH=*GbqJTFNUCFna4$yKm$L8Q>8;Tj+{PMH``ZQafA@b=fvcTOYi^i} zFaJXfIu3?s3O>t;&DhnSbr~ zH8)N9E-Na!TIE;$jFo+$`>xEi(D}EaM(fkuOb%2g)@)EsH|*#<^G$k( zanD2Z2eiUM=W@5}4%y7!7iEk3{n!{)xB8;*`f?Xg z9b(!W9$x#tkcxyIEf>2CDo0tt?CTvnZa-eKV8++Jqcv}!%U!d^-r&a8^h58iIglJC zGH`dU;Ez2lVhU}NAu3*prw?mAy>|1r$ zr}g)B4|KtZ8ySURoddjqu~jY>rmt7o^T*alLopG87?9owF{ZHCD&16ic^Hc`7T@gH zl0CJeOv+wAUg&(Yg;1=u9bBd)e3tumZ#fc1=zqR!2f_ibZa8G#kmlsT6QiBO1!;A;FmjE*hzfN>SyC_PrM4 z_)rtqJLTy)Vjg_I@W%gMDG%_8 z6n|Ktf%dfk%tN{oP~*`r8TPzV^ta>=@2V}k2NP+#Bp+H21OgEzMPOj4>8RUOC&BiR zSjvtAQe&!;5~Zf{8tHKL${K75FAU%3hTm`Jy1|Fki&VP|*DT z!v06%e+uXzt`Y+>#!)eVBg~3N*AO_uQcUJ|XB|`Yl@|`&`Z8T(@Xd`q?DvZxe_?%> zD>q+HoKsS=c3ujK6PrdnYFMioGV4HF87F#i-q0x9zGH_DZ%Qe;qX1(Z*|n)wLGF6E zW?HInE4n z6Z(>UT<7Z+z8OR^sZ}vUT5ldhvx1mNfd;!Dp$2viVrYqSvm5{2_b8*&{J3m!Z+BL3 z%TXB}%i)gvFBAF?peLs&Urp3>fdV2MP8r&o*8+X@Hhf8~D*l!0R3B6ILzrFjY2IPq z|4Kjg-&1JDDUY7bh2fN@rlzOR&qgdt5>B)qx`Oos)`**e>luZ97cg!_)sUG%=0E7n z080y25JFWYyPpO`uzzTBtQb};3tLb94%T{M6@a@W3s~hDOh*g*w z*~F#XHJsY#^6%|v!$h!Xd?JLZ0EnT)_5tB2@v)gTh=%?8Vb{VC-m<|~r<9LR0gA~lfVnSxwxl~6(XJ3EI?cHAa=o2#&o6~G1 zH)3h+H;=hO(?Egl%9WGf19~|zK)_mpot4|`Ic9K%LD$1@{(`CKo}cpUGR*v)wQFs<|*m0mm(53A{5OKueiE zbY^6rMp%6>cVFYDS7!ElTVsT_#i>zEW9DvgedAXC@)?vh3ji-n7M8WRm;!2q-qsd$ zVUv@S3%*68MbU~3Smk7-)Oj4^>z`_Qd~2WbAu2_fG-xWpFRt_F#EWmPDE`vEX*v7o zmE(gQ;w;|F+72H+noDIVvl}d3_*fqPz{oAz&ee>!i3=hri=yklhNHYiIswc+s8_24|GFGjfEJwAes|xlDv>zs z9a8K1?Bv^8?$$ptOz(DA9N~mQoF@vc^_4?F_!y#Hj_$Mv(8|b%%IjnwgT7ht*HN_* z*xKDFj`2}6x8k0Ox-8BT44eDTt}ZqU;TRoYAOJw_Uvuj0~woP$Nzrf19eoE#mASQ{d19I%nC{b~U489O)#Vc1xf29Xx| zn#n|NzB7yr^f>tU0jPlp+zis_x+PXIRf0HwaO>`)n4LmjDY~rA*uca(Vz!=-WDRQ2 z&`oK0*M4-=!$Wu9dA~Uu1s;DF_%e=-5!FOMg*GaCZ~x)?8D#VOsK>T#umz`)jgYt* z1L9?*q*5^jQ7J%NQZarMG%tztU@UL<;O(vXyV`!|JJe)Hw|z7<#+HKeJ&s%=jFob?T_p^zhl!|_j|A3)DNZybj z;{*T-&-IpaV4LAs_Bv4@LRds(V!X*<%*MGq#72s^eEj^Zh7yD4^>2C4XYI@%i!;g-5achSZffT^!1EsgRr)2tJC(>=jIRUM)o5~X zYhJ5TmtsL@7xerp9i_t*Ni-5;pt3&Z4WYbZCrGk4q->Mbpic=^oL9XyKeuEwMOllt zASp|Sy+ZN!kE3~cdFjV*=|Ik5li#e{h3Oh=Q*UpNY})ImGNpB2N5vlzd~e)7vak7-Q%(mE!yWLz&Zr%f4;mIUvXaq$%ayK(!>iNq><;$Qi&pp!+%`0UxUnh#eU ze(CL59@l(O9u8@w1Hu?k(9+r}1`YxellXJW06Dt2=wj6*Sy;?ofTio0F6y4e?cdTH z<|L_0CE_Qie%#w>6;;7Lk)U`>p9aHzwaPaYE)`lIBE8Y^^*O(ho+QDBVdgykg5=7H zE!~kH6KEfvHpaReXP$n$ef(XN=Z}vS9Gn9pRG&W+tK&b|TaPQP6N4{E=9y%uv^S*8 zwWjpHXrFrsn3+IlJb#Zu=f;6$0jti>Pxr#+_ig;St$B`h#&B#DS%XI{IrMnN&WSIo zE!g@gOHz*Ko_wJZP=(|AAm_$eK_JiwJd)r?36wyC0=`X3$GVcK5TvNw>^UJu8kh+J zfiVJHJ_FiZQ?Jh=CtXcZnSY}$*|b~W*93t!&wOqv&IB*LZffYP!Um&}Jy8ecvFcGp zWoH~_14vEvZ)?5B;KA{shi&iQQ;lkv)c7u2jqqK)XH$F=`k#1xY2+w9dEG zf;~ij6_=VmwzS=)88Hd~h&AEJVAxK{NblfZ=uj`*?8+a(DW5y1+O5j1T<`WAiyF<_ zitxW2K=*-81EEZqR^vcU9yR_xHvI%WXyRp!up6n-_w|QN1|dXoDBpFXI^DWsfa3x5 zLWo7xT|65%e#GVPhz8bNn(?iEjd?-5Q5k2iV$=Pq`Inb&SZbN8o(tgNaLmK`Lvk`e z+#snV%5n4aX(iM^A+cqKpv4$s5@^XW`(DaMScu(=k=`N@j~&lKt7qK-pi2SQ`XPwu zu#$~sre}+bP#EWr%0x-02IFb%NO7svtxfxZ*zrKo=yan*V4b50Oi>YC6U%7S-}R@5 zI5%x-#u-dfG|W!1ZQG(dB%5Gbnu^*trspewkpY&2Khxkn#WP3^NU#ci4?8mpAAgWv z!C`dGq_>g zA5(PGGoNTu!~*1NHRGxEL@xxH-0q%rCJ6aqaVbjs#>mo2w?e0OiEurE&OqC1Cz@S= z8@LguGW~8aMk9Kg@nZlslY``U1H}QatN&04z!1WhR=>Y~)zYAy=Y~^Bh3@I0*64A5 zAk_3pSDDfw4g3P^z))Y;{Ps8sj+wZ$Bu%V@9oVJOZQ8nTwSbJ<$K`d;CY#sYuu3mI znt}|Hy>pXdf&T9946N~VKnbBOZjOV2abbt= zl~0Ew|Nh2)#nBLe+$ZVLa|o+sBV?^2F4owvbjzzHS(v_ zUX2X9cx;2<7S!6}*roO4dBEFw-g!x!gLNr*U@|=eEu>w2;)@)?5+LS4VkR(UKp1s% z03-`hY*-?qqM)@R{d2ypsN}IOFSUay0ukV$_hxP?*EF+*P7k%nLEE` zG^)ODsO0B=SqD`W>IjTGD@zvWF~B8%f`4c-uLvyK6DUmKF+URM7x@HS7GP(4sihn` zkWPAjEFGsjB&P?rvtoAY?U6p*U3o(I(m6-Y+)T5|174Q}cVV*;+b+{?^AO21s0B$u z>pMJlqVb%AdHx@^On9W@YsiTLGT~ulzesKEv>V4D(5^@GDU=H7A$UTgvtN<2Ic?pB zC#W?4eN&-R&NW+UcC8}6(wh$eQP`a362j26WOS9@&_z=esR>shFvS+2DF7#pkfKHM zsH*e~eAf71sN`uMl{13ZiJb!im59r$;`zzJA=_fX?wNQ9iGM$O5yZhZta3GrZsoOj zN$2MmrFeA^9s#8xhI8oHHxKX&^a1x~+$4-P!J(pakIBr0wbsZ&%1gzl$e${MB?}1+ z#c3M@g4HN|e8G%+Zi*+?*_eEJ+%@%Sgsb98UV-aujh&O*aS^%7I-SJrCq6f+oX~ei zaVn9>7q30SD!248r96{~dWcP9IfbfW_vGEotZkh2+LNDdHhfK(9NQK+f&`eiWy|(&JIi2@hc0y@d)VZ{N-f6t z%>s2fs~P5J?=tL=*f7~I16fM;F^;^0Td)@sc)JHQ8R1;x+L-d%HGg2TWZ@+_&qKQ< zyC6|-anyemI%dMVBS#%l+tQTN&xS zZXI#AQ25@|YcrR+qZW!met+}*h_<3Jwu_kgDWGPFGaL3vqDAFwXUBhU^vHA34n_UD zO|h!NMij&eYTU=#M7@+5**b;aZM@#nHQIl=8%fHOaQrVVtSuhBobyMjeU;xm-2Lg2l;ZPWR?u;jsRH;c8caDSpywjN{uAt| zRkM$BA<^`4Gcw7a&%U^tfa#o}T7d^XL2NA+X6qMRs&6q0-OtOD>B}r-;Lu(Mn!?U*);`mmKmO@R6j55mh=D*t=mNx<1KnQ#S&dI^Z4&uk>fV4Ov;gvP zghA#fGNqn>ca)1`mW{l8Wpt;uXmC6S!gN}?N2o>!kML25Fo_oCcskGA9_*E??j3P@ zE~>`oqY9)9%zToRFw>`!;y(NMo_1%v;nuv$E?4zaw&~Wx&veO(L3=z63I{rVk*9m# z^%E+F@1MLBrrPa#a61+a<_Y#h5u$ASCkx>xQ{KB00L)F%<2XPgs)`-OQ zAut)&)Ia{^F}PjBJb4e_90{i4ldAWOX{D@V(pAP&+FXlpzkTYh{J7tI{eqFHX>+%A z3x*A7BrdyL1x5Hw9)bbEBQWuV=SG$-TQ)&DI;t}bQ7~`o%j+VrYWPbir1_`Bdj?-U)`KVS z5t>-Qv|H-*%H$j8$8Q^?2uMoSiwwM>DuGM;5KRD5;3r%hpV8ezh(KtpqPZ_6bBRDw z<4Y1GSf=94wJBm`6g`CBZMyD!?=o-T#H_R>2fZL{h@j$i03rmSjt#`<37}>>5tA~j zSu#J7BjTwU)qmUH&rMYoRH~8@cU0y1La4qAx6c9-MdW4)DPQxdG?{hLMVR(u7V)o z=6J=~LJNWfN1}5VaHFv!L&P{#Q7FHVPGh|@?b9l|I2-!z|6*jb-*91K^tp)7%!X{9 za{Ef)`iasn;rx=aaE9tUY3KkZgjtF*s>RqkIppp06~DMagqwBA2tSto%5iqkHbr$= z)9!5vDAa*;Wq>&|a}7vEJUtYAvlpgQ78+D%U#o&&-7m0!slhP6X8rnOpShc4$duNt z@tTg^(92EX4}+_=qdgiHs3sGv2Vum(NK<5P2UrCYJPRW{GjM1+i}=Q`BgM1O0zl~A zayno89}VhcUzB=ktHm4?dLEMfH5*kfL_#b!pSKA5;#{hbQxchw|77ifJ#!@3? zpOGlPY*K?ko_VfbwFzaIi?3fX)6Z7cDn=MnMtsY{=^Uke9rM2)S;BHzhmSR8Y@)7D zsCiYHDilOLD>j}z3ZE6y==KCm$4e<$XKwTiGCj00N$&q1%X>z|T8qpeo`Gd-Am#*% zol};$^2|jz%tmzb<+3?r3ca5WxGcRYlRGXf{B4IfS5<~;aZOJns!lrtjXZuH z9{UNc0<)8Fwp&|u`utNKhhm-DuoP-b9?y2>QIC)BGR{)!+J(mj+Yfk{Tz<68fncVG ze0mj$kni>A=xzN`swlIpvpQ#MeD^LxD!GjKvOQy2!8UgDpDaDvioCLUG}R8~+K2lN z2l4a;EZg+{$+0HDJ{TO6rCG3jZV2hLcwiB9i_zA&>#Hk6+8;jWr$k=&zwB(n<9P^y zJPmr?2sYG!0_dc^)@~KmomTJOaDB{9AcV>%CM|7DP!_uG=e zxmeGtS5!T|w!H9=m$F2PinfQx6Tlsrx#`8Be+!UkO7ew2=7iBqv5}@dL&h@ho2U1u z-+jg&Ts75ohMj03e60S$#b6D+=3+1c2T=BsNdN2~{)jv+UNu(v$AuBCQ(d9sK956N zyU~^eY5%=h$;<(=IjQ;6RZ#c>jTG2QBXE;9`?5?vMBE9s4IOhBx?a<^kB_mf0(~Q* zaX~1Cq%+^q0X7?bm~1dbD}q|~M2k~s`wG9WuKaLv1Bz7GC4O>A>+z3-e?KwMGVo4u z2(Cb^c!!{pk_F~32YFCx+nS%6{ci9Ll%gkZ1*3W*h{6K>Wtw6MCOZT@jlO@^{Xx$V zkZ|`hHhM;psKWwV6DwcEu|=)=x%XSn_A@glb}akc?P*{!b_7#XFDYwc+PSX2zBib! zuh@qiWFH|lAd*-o3@8h?J(!&>EIZG)*p7gILc9#7wzc>U4T^4x=ku@`Ky5ws30 zl&H>FZ(+GyZ>VV;S;p=pt|X?-7M`~zIbOioqw~BwOSfYY+WlzLrN9j~?6J%^x z$e&21&OD$NtJara-LNjQ#_fASyR{P<0}wz~u%)a=sd@%s@I6AR<(7Bdzi;32G&+^H zTpEnx&D64S>|EVNU)8BGwVrnl|BhasdG3Mky50A%e?BW7xpK14+4}EI$iq+=Q>n$0 zWHZ+^>{`naGjvF6*bi$gH^7m0!ZIb8_Zez&G3l|_mfEWr>e<&;1jH?!?Eg_*`Yp%Fn!x=J<}M64zU(*sW$kEqQU-RZNHSbj0c=VOPJeFUfxV4$?C5wYk1hN=kT3sbF|yWHX8RurQsc zM|*M)O?%TZ9_C|2TrTD!G3Hh?eigx@-pC=`b3qB0R26^)6NU8`^i`)`t=eyFtifCQ zBG7i%dfHUj<7T12*Q>^@ZjpZ0^^0xfDps71#WBFm5RQ8L{GWV~8Tav0ymZ$yg;1sV zw3t=3_>`QJCxU>5O_D0DfP%uruaka<{l?_|(owNwP_MKj^SU%xOYsbjd126pZ>(^D z8N>RgbhAg%-kKrZf@M5DhEQ%7paySfrfug}TVx+LJbM5hU*Vur&$ASnH_o?YoG=LV zetx!(4w0HF$x)h8=AZQEcPx9zB!GB`L0Go2NZrw#UH)V3cFWi=dUPft*sD`!KHMc_ zAa2(JbvU2~2c}kVVZ)-2akuPmI5%V)hg7dI`M zvU(HtBH1_l;J0#Qj+d&2;^G7nTyt>3IaHgGD_{dGm1#Sz_WQd^;1u1v068z=P~DM3 zy&#Lh%0Zut>c1eD0ws$J6Is>=936!N{53djXy1@lGthuA)qN_pvDU+gF2){!DT2fq zpRV__B5bk1)Y8T4Kj(`Mbtq^eh)y`>ja|e4y(5=?h?hoCXXBnc!guACZz6A7 zP|L5YU9;Ox7ulLWK)R$$LPSJid1Q`3mqZM+$k1lz+RH+su6bp&bkJ+)YaoN)J8U~e zt{26u2H;l7v1ZL1oh7=$aNQ#w52R%MS_**?g(;Jbo12@XWeb_jhCUL>v17)|)o0gd zUS=4EO9ID*@5`;I2H5-;!(w4DgDe@kRKWrHPocg1u$F0ntmzWz|_~mTf z)KW6<3CIjPh2fBti|7(O)U#JS2d_GHvZxo;bUmtZyZ>>+NmJ7-L9%(r6fj=$RSm!)b>$Z>Oi?_RoKIsuwwTx;*Hfi0^#r=;XBQ&23*gziPY3fYS8C z2C)e%^R;UvMd6jS#vZbroNK{AG{y3!tSdW>hehSYJSFTdGSwibZK|osn8wR1MecxV zZ}BIOYe;zy)o#~%x&Wl!S_H;VG6_iYTA7MlACP)_a2NT@V6B@4Od;nB3?7Or|2UVP zd#KfLDPe7}VW8nL9L+Y6HyLK*-xw7&dA|PxGVZ<@H7|raT zkZs%@6W zt4Ym!a&~%2ihKDOZFa(DmzJAB58N6hJw}FCm?Uk&oRYHTYKs*1^pkdD!Jx8;E4zi|8B=LybfMs z9$^0y-DtRU*lQb4G1B7w!1yua%Ny1i7*m#TrU%if=)y(>z994jXmlvoo;kp#5n53s zgjRdR&HUI%Bd6ki_}Gd}ua{`(T4d0vT!TgQK!Y~V$Fs#_8+~=lGQuJw9lO`#`22Lm z^LMP1kEnfQi(8tJRZD@GRTkDsk=Izk9(s!yA`yZo_~A&DawaP3Xy`q&F;^9(9S_6v zC$GBR)jDLoJfTar$)lmRwl;M}YH5cxQgqsSM6Zz4`PEL<1s=PI4jOt*%Q%m<3VJDX zl+nHZB~0hjDY?@$3;p{{5+%u`Oh+ItXJ+DAueui@YA^*6!k~z+NX}`&dr?hYoYCne zRoinACD94*gS2g?9CU~L4QW?E*EX>6V|sY;PQCGuI?ERHqMO#eRCF&mWb4*X|2J3U-NtPP zYN38N@A&wjJ!dGY>cH;Zfxb8q#3up5KiII2yQkpO zy|mX0QT$D7MQ6Ubb0%Ni%~!NEVkHAmoBv`K?+F5|-MwtprtW>7Va%BjU<{!S%V_)M zp|<+my}S3)o&-P7ZYd?VXYJOPPY*x&dgO=ss$G1H)ICJr2C1nf^Iaa^T=BD`vKl?z`i=GuQ3S z^%<=298ZaDIhK5)X>4q)kdrQ63u5QQ;TwUVKJht#>LIdYbt!e;PjV#wM~I>M_4NfV zl@Y}iDO0z~Iy0>|?ubY#?z>s@9cR4B#`7S{tfQlA`k#0SMkB;^o6v>9$Kj_akOA$lFN1WWtpAH8s*+w?wr?+_|3DC@7F!?g^xr(04d!WOQaq^wMu!a zBj`C=;lLnh!6PEV5b9td)KbCguN(Gp9h(W#x;fA5?2&8tBisA#hIa=yn=iP3f6=mI zv-W~c(*`8s^o*#zu@XE1@Q&}{X9E=)by4BhE7S3yDMyn>Y7kjwMBmWM)e_q5{jU0K z_4it7^X#G7rsTe?I3-u;{OCqQ{^bIE$xMOvBJ~j{ys%%=p&e9oW3jKp`K~;3Z8$ox z)?9#{L-~A&ox7=XQLq2~NR%Xb55nQ&AZp{}NkDqV6ApVJh722MvrWorhsP(`&-0;L zU)rTU4(J;gm>C&O(=l$fWyQ+vsi$bqkh`fym@iF>em4m^$@<=&5nf^e=={S_L2 z8g%|=kr5n&69Hk9VW$RAa*wD91WvH3OAScjlAdlp>|bOB+6IA)5tt}ic9gdUFt+7D zLc6`9Yvi25eKI^?voMtYT^Eyh^8aD(O`vk#-@o6xfo_D%a|21(5}`~@GDIYqHAsep z28tvVQkiGUOew=Qvn5KxHgDsWp;ViYP$;F8^SbWr|L=L$I_tmAI?p-hIj!Gs?Y-+B zzTeOH^SOri^}gO$>I4~cL~&Fa9qIO1`nj9W&~+ozTiPm|J0U?M(jsaKy-_1YbWR}4 zNRJck4y~*4BEU%%^6F29?V-?fg+P~Dw7l!P!m3Y&)Od&JTmF_K3-u!$N8$HThA$i^ zRuZklV;?@uR*#)}xtHw?Re-4ZJI@_81Y|%%w8e&&rk3_s35U_byxyMh&eneX^yzPc zrzlLvAXal`R)&cb&l!*keeU-)YT>hxzl7j>fEL?MJQr4c!=rq|7{|Q~+d7!=x=-tR z%-&qqs19-vX|GFyX*)~25>>x|ktt9&oT=AQyHRQ>EZdTv<7>UqMd+K#@dg5kjA@fvED#*Kdb{P~WXzo0g&lDTVtY(#h14PhINR?! z1Txx(hX?<8{kkBq>dJc15T78XByEWhESbpWB;;ZZgG_$pzC z&qJ`NrEh{%vA^|w|MM;^t_voMsA*pdnNk`mWbgoNXkWpeWNUURks{&J17@h_XIH> z=F4!?!sJ(L`!4mKkd6|T1n!E<_g;N|2iPo!0>6t=luS|v1xr^W|J2nz#@UhjLZe2F zpd!}#-o~D`w~~Cvus#RZ&V(K&G|{D6T*(JNOz z1a%TI5E_%Hwl1IDl$;9%%Q^QK8~uVetxdlM^^>MTdMXpZOF_wQO+P&oM9-mPjc_Y7 z7DuMK$q-`U^?&>JZT)R#fv>HjX0RNQB7-aN3+XL^*2t}FpjN?JBMM?|p(q-RKMe#M zokg*qxn_T}<8HKGgdzhV_0spEhD5w@ZFybH>5t>G>-q!^71azZs*#b=W{A)1Db{1b zw5d}?_fPsS8PCAqmR7}3W)wJ0VnT&ZCq#nbiZIB;M3@GzKFbx zM-lJwT-t5B-Q>*m3uxbv^bpX|{yVGmQ!q+Bg(JjH ziC_-gU?EPt`mCAd|B`(%l*Hh$XUi5X1TIi2GSXjtre@}dT+VYE(M;Sf9t2bUn4nn8d<&hPiU?6n{^f+@J#Onu_(4;6q_s4$9%^F zg>nKmOI#4{L8O&=WRKchks;WKo9yjt&JI<@YH8ab%LLH2E2bP06h~aB@Z-lf&s8W} zP*a0~A!BJ6r55<+P78VloiBb%O0p1zM4R&?GJVd;G;Wu@Jd*I^wEph03affQy$1zM z35ZBKpRKNGedEN$qqpwf{hI-C5W^p5Wwj~lyKyW0U7A&F7Fw!ernJVgnlw?+Dk5{L zIR(Aq)O1GSRD|kI7Yuxj!{^SKPj)YuVfnSi@I99OjqhE-6j#4}H1w_eBt9~a4Z5zJ zI|w@~*Q{yZT4B?b{F5lZ|^D%EQeS$P^3Mc zcOgqA7eVSc#_5uQ>2Q%DgUueKp>IsZ@JOrkA7B7Wl{PXes5?6I%=*(+XHNgBMeBMrmmP-5DjaLnOAxfeF%7m*IKU3|!Un5GLA7lwK55(S zl6_%ai9#d}^tn{|ZT-&v{t#X$@%gFcru=jjQ9I9u3aDPad$U1_B%N(-)hW%KMetCj zXAuA_x;JSIr~%r#nCxE{+G^AlFFnpq95a5rF(w98>(kC170v|| zXo&(LqIb1lNd;US)WnIm&MdSS(MV>zjWcOXWT*&}nh%F+D@;JT6@DMvd7pxy%%JT~ zr9%HqZ#n_cM1iI@mWTl&BU)H6+6P!DbTr8=41fm}Wqw#%c7@n5syc)f{ErdfBP^=5 z>i7M_;GgHofkz-_9cFY35Y-`C*4Th)Q!l!Wjh4+-rYVFw;iEB(Yz!l=wD0_jnJU!Lhg3o z6uLxd4SBG;{~}=S1ma*+ok&vB)zA;c9*2*7kez*8>LZN%lga}3!fkJki5c?mh3x0F zu|dX}$DMpO8&GG3Kp|R+9}z0gqHwO77Ecol7AW}hwPru3nr%OE!c<-T-;Wn^8M!BH z0o;o;M`0EilR_-1DH8Xpi<~@ls-5U$;aRpYhJ%ZwRY>Yzexhy8QPLmnk{n=2rMk+ki1{|m0fz(6n1P^O zX9CR1?(5WPRFH+9NA+_vxJ<}F2#T^2rZ^?J#a*x_45Gp^oNjPUxzfv?6h4I?MEfRj z#N0r$?TD?jma;FDO_;3puXa5fdl+|$0w2#k$5mC0Q0O$I+AM@j9B)U4OY*P?Yq2S^ z1Bo`EEFnxyR`jjIjt9R@JQK}(f5GTDNh}bt7CHpuAfZ4E>U70)Gfds-Jw&OUX*IUj zD5(oQ9~0J@Lk*dgr~scBp`q`kD$XhtRd+Cx(pN~DXUudrE|HfJ02#DaSl>|MW?US# z*%Z^yz4-g#!~IY)kOR8$aen76U4|3Ni`k%KN`@>hO_doT0?_k_<+vIR2GbJB6tawh>bA>vn-%}eJrA>WFFYpM8Q=^5?%lM}DnL}B zDXj;G(SPMRqbBG*XAaJG7xARgg{%?QYKVK-{kyey??$l^tVmRhv=o!QS?}9iXbF zw2K{vp^EK!Ly%YDO}#ye0RO;gjc zzzLP4*XgRG`LfZT@e0!##Cw)!w1=YI`G79ho{&pfEmthL6SqdQGb=QBy;}Om`La$D zK9h!F$9UE~P?v>or><^#;MelR5MC|*{gS!N6W-o)7)_v2Bn_j9&Cu^BoYe6SZ%!^p zLc&$h@7ES{No+#Y%fYB^pk8m5Qf+eWOeC0Bu3PuhZe0Vs6LU00JrhGj2>JvkDcXk? z;kR<7iH*caVg+P6q4x=5+*%R(h!$N@f}~2N&{0Z)PcjiaO3$oUud$qSnN%P!Dv3Su z7!K&mZNG3C6ag7s!eLwsIDv%K6|K~Z&SMdosk%YGXgAdlMd&yG#8siA@mCY6r3q$) zlc25OAg2^wI(uSgc*i$HX-}UXq+xU5;K8$q(%AHXUcZ}b<}~_YD%K-nq`?nQNl;Ql z&LhWljQEo6@4#WAoo?f!{MS<*PO=lEn=c_@5Z@+kW$0syG@TYF6Z@j<#ZYm0>N_^R zUAtn16Mw{Z^nhr_*Al@Uq5+GHYUj?5z1UR(p}?-djBfO3j+p^rVn2o7qvTJatlIQA zSM{MH(R1D#2NI+A?8?VdoN3xL0n#~;!-&U?Pm>8UQYDpFy&R;E;- z0-(91v}%MkgCVRqJ!+-fCH6#RmOfr`36d4DWHf)#VEiV2xB+bmv_Om8>9uC=kMT6q znn%i<5H!rKRf8U4mS39!(a*{H(w~@b0+hpmxAprKg+l}mJlh%-+_?=C*W+$TDg)`` z0A6JHgbPQO03bpmM}v6UHmxG;o7uF+iXZJz>q7m!+n6P|uQ5nJ3;9*qY)WSpNg@@y4ob;>U9C@d%S5^oixd51pYxh}dWL=HprH6e_|Z69Q+I zxS%mRmMxL6WyDGTfvG|kcPKjpUaiE!6nSzL>kUN^_5AtR>Q9q_9a?wSZXmT6U;?qx zz2ZsGNX4|%{+Da#xQ}Nba-GtBKwAgTiD&d@@Bl_42v(s;NVb+y12zk1v#Hn=kBH#7 z$$dyk4tH>14o7q&tAS{8NaP(ic%3LKlgT-a8nsa{4K1Y&WIQ;~22>i=CLhLzYrU=) zx2enj*@1B-m|Qh^`h>pH*K^Nr#!ae{dRsfXy`hHHf`p-n=_F(px*cra z$6(YXU>1-Spkp+F3i%HcW`BciJFr^~jX z;L}%4VcE1n0~z2O5m1w)Leex5sebUlNtWn8XQ=IGvvt?wI1WU-od^H{iy3*r%byzHmeBA8WuZP`k+#F1aT$Ka5dGlsN zSRyz(P(TZ7oyxv+aVty*HtjOePFdIvUJHRZ?sgNy3!I%d0l@_PDD(dmXi=jkEI#Db z^I=Pk0v*u4LeEs4?OFavpcZYzhAJ$-rD@dnyHd37%aX=T6Nri=Z86UZ*hKBS33p8_ zeLL4rXZ;>pKRG+INUxzlZ#L|Rd~9y+kFDA#zA-}x^ z+=bJa#mopcnq-))dD($QwFT+gx6ej)m%IBO26^IkZUqlWGel_n?$Pj~)Uw$6ije61 z{hOTYy=ARPFobQge`3`qU?ZS0xIkLohg(=HUPbi?(GjP$C`==K zT}Z*C?1#iM%JjiFZ^_;94fm29xVB$0_+9yI0UGLnh z*H%;YXi!A}AaSwJpLYT~GY;(q21TGrED0Y~T`lATOv&<+<6*;9Pt%G!%csI<$P5`W z!NRbg6||B?bQ{R#zYl&veozgxMHirILemN~8Gt)t-md+d*b_Qmf08~U?wXdMM zcZ_)qYBY*tEzY>Rq}Y0* z(I|6&@vekp%rVz*owNAF*p~7Qr!hrX=so)Ctsf1%i|*VzObDZrBM7t3B0j+ivx!f? z)G0G#<3td9D9RpD@PBHs!B%P2LQhXLx&vT30w}qsT*_rr*3w!J_A*>4=gJCc<|5K~ zv}WMP-XYnQiP-O%4?Y?#gJ1dA@EwCJc(Ghgf5)S%kqocOAqJCsOEExlz!5;G|!S8~z-WDMOWbegYD!obn zV0LSY+q#BwNk4(9m?=wH_23%XvOt+`c;{bw9n3bWF%d8#5Fu(X#-W| zUiU7 zy4gmrOJ`mW9aJ=Z9mGK$KW4rYeok&$W9kZmRIAqXcB`2|Nkk0RI%=PQE<`b1>9Pr@ zEAR+Tmu?$&2D^z}7_lszSjtZI>@M9wrkl8ec4HZoBd|v>v&7FZK|Sxyn_H&Z00JGw z>*MNit+q{MJsBqR8yJW*FN&bem)l)uaeI9Jz<~p6*MEDYNy3w&B2)8taBAvGWu7!` z;Pf?@*uR~7UhE^P^}mwMNDm;%ZGNWhL2>g+f>mC!C<;QWM4bBSGL={ALF$&$4v3tU zHvl0g`$Fx6iP)^!&a?s_c3VX*Jqc?>pJv? z3op~_>GxW>V#NbQ9x*rM4Z_kQyGE&=-QHFJ(^BZ75g*)|)>T_c2bm_* zI%FzfGniuaR$2D9x3s+0N@s&9&GG?~7c4j@v)8*IicSy+`wNu9uyu%j!YaWfLjg_V zfL^&c(P&3CPZ_iJ`YXADK*A25qu{ALQ4qr4&9Aycub*+Wha3|}hh{yan3dpjU;EJx zU{WB~Koool(A->oW43G=XtCaqJ=Z{Di5$nwu=}mq@{`TzHU2m3zH{ed@=H@7KR?^Y zH*Q1|U{>F>u$b`B4I^qn2EY7)B8g0#mf{075lj?Av8bPI_p`kLSn^*Rzu6$IyB>%k z;fXsaHTx4tbFM_Mm(~^Oz}LQ#^Tfg+Ek6L(K2HVxgcOFT?7M+Iz@0FNAsV5BYUkWz z(YM*@wQMmfD%l^gJMQBCVOi@Kr3E-e^Z}MMl(V^#&a-UpFsoKg8;uw+K$tT<9 zusNxG?tNkLgoK=S-x*TIBcY+}-| zfD%rr$EX9sagrX2Igtd7!}`k;?{u8(+Q zWWcW<_iNz!9D4egd(?voO;yQA3E8<`z4rv#59xzAK&v{%AjuEOvLe3f)?*|+UDIo- zGcfc=_kqSNHC@6n2R&M6J9D1tDgoL+H!Lm~UlbSH!Tfw17m zXO7IOCuqi{?{|Hhw-67gUJDPnOx}QOmcUX})xTUTXzjfO%G9&|koj!$6a)Y11ap?VgB6OQY6VdJsoQG@^sV_gu1P439+hLKM*t z*I^s{F0x$|E~%ZD|6LLZ&ZAbb-4U&6dNgck$CdtD%1$6$F*>Y9NcGRzjzWL9^`GT7UneIUhnGHtDzJ8KJ<<5%7>oi@0Z?kJ zYuVF1tX0dF#TD5<-9&k-wdx+F(Ac^2Dt!k5#TnS8uejKig9~&B8e~l3jIa#Gs2W$c z4EqF=L6S9x`qb1Fca}b|`D%fXD3$(N>S=?!qmM!XZ6+Fga(F$O6CpXxpZ_g>>j3Pp z1OXTs`OQ(fzvuP18HGQ=u%TBZb=aLn8tOQnQSJvS8kdNZC1tanJHfm2>!mX zu!FMtSG9a2#vT#v+H}Jh6GoErJd8vZU)Ux8!>{U|+hN*_q)i1EFE`bMC^B|FBNBgo z`!;fE((|RJwFYUaUXvE@5pdrHr=Whfm_OeeKGVOS zbdCXhl5IxV%)yB z_C<1-#BNL;WoKvS#rD$lX#1Z}va)g~Vd0aunYhxwX~nk*IOe!^$AcYp;OME|`A{Oy zr7N)C)pxd%;smIgPK13>ircT%O?y3gfz!O+j6tFdTT5N_!jQRQ*8t_%qmKrvDT-43 z+ER`Xu`!^O#c;l4s43+p%=59&v4L2*8VOv6#<>trv zj8s)^78jyG0x>4{Z33QpI@>5s^e=EG?W&g~r!R+{2KjIbBwLs}g}1k@rC{a_63wl+ z*Bnm}eTC>lN|9LrC=pcxev9b7Ty{Zt7z{Z@Aqy&s!9=to#KQAB@%c_;q*CtR?s^H} zYZz0SS>d!x=qZDljd6C4gZd!YdDB(PC;y0N%SY8~)ArZa4a8nZr31*LGk^~qg@}K& zq)bJq@oV86`eQMejeLkKpF#`to|gN{?jt5LjVVRdYpc1oswz~Z1d&#t0c)&uTb1n% z@y$%y!2T&}G`~fS@L9-xNRUf=pKykg^R`ZE+@{TN(@pVb&u+Opm6uV)Qp@oqND}-> zYCO@=N)e<){r*k|A%Cfq8B}Yn458<|gX8YU%;W$&iznI9xz(Xax zK#xRJ`iL|k)YQsrNvJpr9_6nsd1t0y(NEt$bc%=l%LOR>YuS-bjeh(Ln|pd=f5Y%v zeiPE0>Z?tdS}R(8it?1*46ifS*Z3c8nKY^bess_=YiX_R%xF54IVm2%VdeD)BX0$ z+x@lQ8i}BBgFS=)I`sV3d9KplgXt<_@*`TVbs>XNb+i#3T_Gr zzNU3=M94!M-zjyu805rWjbrij`M3o#Rhv*5v(|I=Q&YTwlW~Sr6bOkMV;wa~&U}Dp zq(FTvk)0DLhBEP&7BhR*!-XCykM)tak3x=Xrkm%LrEG)gqCUm z$i>rhVxbkX019h;O+~Ab(cXafQwp3kpxFI>86ehV5AR(zU zj{7tN@W-;U*clA8QyYas-9V93L6(xhM-%=sf1y*49*>WFV?3e*A#CD)HEv3~lZHY! z2M`F?{t)jZSSTxcyjFxlF}bLSI!M0=@Hi?{%o8%SCu;jrT3Y&Uv82|NXb-wDO+7*p zUiI$d$1$Q5qTBy4kCmE3(Cg@UR+iUwZh|-Aq2-9SoP@*F+|b5!c5&G`cutr+o!Yez z4pDuMB91swYUHv9&~+beXBRPec4>xt*in4g$R(^`+nQU{6kYvEO@aEotA2c!f)gN8 zX7Hlhw{IV!#LD$3W}JNSQTC&dwt%%D@T3Q{D z>_aq5K$&pz^E)wUo$kl68uw7~Kyoi)C0o~8sqotZuMWRYEbb1;yk)m35tC+Tkb4F| znCQgjWvSBuE1$EM6RC)FhQ>)1YS|xM0HE~3ew>8AauACqE4Abyl~kUHL@CrL;rnQ$ z)`dfIpPL*$4f|QM`RJO8kdX{}AueXcoe0$N$mf|>}{W= zHe9}yRDp@{gwG`HC8V;kZXGmkabs>l0QpH>u*2K8x0EJWkpVNCzFJ*} zciW$RTi3$RnhoE$ZS~D{m_<1naF!h|RVZ$CkLz@-CspbLMJhX?xM&0546qo;^8~0_ z9vNBnE}QIMs1}WRa6XYvgVYoWa=P>KXsa4Y&BSTq#OLmsS9sjcBNd7y13A4rnW7{T zMv}MusH{XzY1+y0hW5fkAoeyktlpfyPms9*(+#yBu2ztfOFZB(=B%j%a4k zSdlhOas#GSid&8Rtudx(i;@5WOQYZi<0U_wEPljp@bmxNpX3zr!_MYM)|wwos{G@B z_n-dXz48C0l~gwvC@Z8$?HJDPQ~2$AyC+Phm)7eF@A`e};^0v>n_cjHLG$iMz3DI`O>9JFJ`;@`WD`u^?1!!&l3e6&rVHi zX&I7qC<`>gBH1de!~2Ze){>a&^jth|493=4HGZ!s6SL zYclOO8Ogj}=oGpOec+8sX`WC?1j<>o>ye*pH8S#oog@8_c-nq*t;nB+J_{O)@n87i zJj=L`SewrEfoyi7t*-|^o`V(P?JW@#TSdULW5M>w`a0=ndB#$yku-pd^(onU<=x%Mw>Ed& z-hJ9iX#yp~mf!+T;J0W$2sI)uAY27Y%a?HlB#VH2BT#x-Crx|8l!W635WyGCtvDBj z8zt(0B4lQ^+!eiy3#$wUM2a|+bSDVjh1(K7D7X}y0Dqb+VKqa#r3ThSSNGHBjF<9y zA`86{JlUkw+XMgc&6LKhlLWSvyXT5mzvx28C zZx_ZVKCP2}+UXs~asK9dK}2-|R^U*@yYK`K`spZhUFhHz4J-)vIcF;@=Dr>x!LW42 zR8>}#Ys-}N)_Ne^xN)%lyv+!<22lH;v84iPp;IhBv=AWb6 zJ@q~db646(o?lo1*7yF1TA10x>?lKcA`ftG{rd#{*nI!~NGT`?z74R#=<8zyyyxBH z^!2S}g{cMin0iB}aCVudrq}z&hqm_#JpAd>&rm_cSaP=)m06FDdm=2bO}IiZ}Tk?vV=~2 ztMo|ot^JN2+49V@Xn8ZYk?cG)7hoE^YWkw*{14-$haf$omZftuOapjM2H~#s4H1gm z?~>fLJbl1MJu@n{0%1{a-4j-I9xyg*zf&I?oTSH-^syv1IeN{SzZ*IB+b7gsq6ipB ziE6nho_|?O?{P}$%OgaxQnKrJFfF{uambLe!7DE>D*OIjWM`#e z3N!e2(=?st%@4Bug`vae={-*U4*f<*nlh+-UEx|UPQp$K%1v~1MCrEv`|~GR5$VdX z{5vP5XY&!*0<-CN?t?%>zqRyw(LMA>kN|ctZ@wh?_S_ZNkH~x?=i>=H;?d*AnR~rx z*s|qe5!hj`ls-SV)T#qE69n)PwNXZuy)U-$68Z;Ocht67GiM5czM|wDZ4}+l%%Q@9 zO3jKFj|W;?hyR*OFGsh-y6bWTQ0I~p3D__*dB*jaZl2O#v+mhX7;VIJ_Ydk>JM_(+ zX5+<>XDWDKpZknk+q~E87zBs1wVx04`{(Kk%Bq{jEyxIr|GemDWobd|jNL6ZFPTTO zB&36PsTH4I*&1{-FtA}N?ZbHcO*QjMo1uU1j${_`RMGcjW$oGzMXZ~~Et~T`>za47 zWy1K+y)3cc6c?*r?o>zaGNv+iN(JZcn`k3N%q6G6+0(I+a698~u8 zoBmuho`enr!r5wl_L=d&1s7e`5&@1qA)U*djT~b3I>imjC)d;X_VNDXL(U~K5rld` zg1XQ7>DZOQnAZ`l4sA1!uf2oFP+!?=Ww}vV-fkufgxHSjsC#390ZACvV@D6~$Huj*da2Dp zjEd4o^Yz&>K}XmC{1%lhsp{4ra_+8t<@dLHN}rkRx9WiZLo~Nx{Rvt(lKfxEODbkB zsM<3xPU|W1fyUZ8%Fo-DE?ZWTIq%-*h;w=fcfI>!vJ9g$j+)Z)N;8UAqWX{=;Jt(` z^N!C=EEs3?8%LW&FCgC+%BV3qDCt!#pfZ&s#WiVLstug2$L-ejOP};Sv`6}$;P)K| zG`bb{GqPSAQQq6C+tX#RjebM}kN{z}ymQM9ryVHy_ZL?qYBegRtJnEPrAW*mCUUF2 z@2DkwpD!6;&hCJ<#lL!0MR8v!}Hq+e!$Svlia1m6dG-`a)qGb(9jO0$(_A?UuG8e-o`F1W*3H8 zl^0UXYtpji`=a?S=jRTrC@oxY({k*%an27kZHoufyeC$7g%M~YVk>|XHlK4c>i47Qij+(q>ALmj zUwfq1mD4YZ1z;8C6)v*9E?9;ttE z{>Sa9RpqlfT^V+N+GCCH6%_^hqICD`JGeO@IQe07AdMB}kFTCTb^>*X8Z~QfcXOOP zIVW6u{XciHIB{Tz7Dq2%U)J!Iy1Kd$krIEOm6_x(n)=JV)7g||ZrS#bF%}-2^AN1K z=fW>jYpeftK6|9*?zf*V6h1lOab;)nUqqf%V-ABa5;j8iZBblV{PnA|m)Aidflj%q z6gPB8Z&%`h1Nl^q!IyemT)Td~&Xoa+vqwJvgxgGM(z z#`N-`Y*X0oUR2a^tH&LVzJ)Fp_}(}WoPcyw5K%(V$IqYlne43oBlCQNrcJ*so7c|5 z;_1u+cW{moJ1soCWtO_kLP-3yfW8wfXkf|vF}xdS^GcUvHwpD9@S_#A8lSYYJY0B~ zY^sFByZ+w>T%~$|XmkOEXVPEjoI553Bx);_BZGpH2zYzoCJ7h+ocXmc4P4R(S^i4z z=a2zcYh}dHjhcA$9vu=?Q?X|k79RanP|&Kl603%E!ZvB7H>Qs!P;snZYx}SFqetSyU%$+mjywC(V2jEm7@Wl% z-R|S|v~o^xcmU~B{D0!(j{uJji}k+1CA7#pdfbp`&YKvh9D+|)s);m#NPiuSBhq{S zp|59!CdJ~D-h%KllCL7|*DbsWlF-Gh(9)sT3TIJ(|%G3i%}b#YidN94El z0|FD>aYA+f9f=>Tt^+Gz?J3uf<iwL<8CD}9Tr16k>*XQBerQXr~E~HtH23vZa!Y$Dbysc-WUst&)~RWf^WjI zxxTX%keGmHQUfP9h_y7A^F{R2B6t{V&*M>gp-+o<#8MMnj5wUkW*OY$Tk54OKHwop zlUS%nbuV#Au1S8EN9xzZccMo*>s_mTg#|Q1A>q0osi=|EN4~^d9wS6YI`jDWo7vg! z_*An%m-6r5JK|v|j@Q$&H%j>Vmjql?8k`GGy!cp-vnk=kz9$yd{p@GEktkY-$;-6r zi%k9|qv74NBAWvjF>%5x>Ej6;*?_ory|Au<_d9Ewq#6|KtEs6Gx%bTS`|)~{W3kLh zB%=TP^pr6?<0HpY4-+VDpGdS8o!emx{-{S~P4w~Ij;DOv4p!Ok4-@jdVoq+y&Yf=u z#DL8A>|xH>p7pSRPtUD%Jf!OPc8YGu!Th~j1bk|7w8K!)kGoH!qv zRKnXNp3)=vdI8pS7y0z)(c_(z=3y5M-_vT)g=}UAXN}Z3-*fYi+n0W<0)l;g()AIQ z#f@f77b+(}GK8S#_qB z73C5U{*$A=X)cuYduLJLd6|_Cn`rc=y`o8+z7J2?82k2Km{P9PhdMN63D;YH7N7?6k>mr&r zY7|Fg75n@fa=h-;@7%`dQTvyjqxIv@>EAM+@}=SPV_PcCckkbk-*ETl&9D739?4r; zK7C8OM>*j_%BS)as_+zVTDiT<&d$y~-;CHc{^ut^b6Ymko55THjcX9OWJ>nfDVs?Yul>IiYLzXx3~we0nQH zP+Lpne({tgd6W++^WfW0rksrFV=kR%#C++U3;yBspWC%M$x2;Aqs^z4bku8Kxs*XP zip1GH&s43skC9aS{m8iEE!|!|I7OU9dLEOT4Shifn-@=+5dM36e{!A?l2|aycEEt1 z-C;{HP_d?|3DgQpft}3`VQ>`{Igzn9c4-uTM}}TXV7ojfSh`&J--u#{C2{pLqnbwO>O@CvbiA{QUQZK!997PD0%}l?< zWBOm`=ofhO^}@pR^B!+*o^F>{@b>MDpfeM8+@0>-xBoRvmA2#8Migl7E4ocT=1gO4 zaddw49ohm+OR`LTr`9~yX49@+ADd)1{<)a~fK1eS)j-oW(~U;*+-Zxag>Glg)|Kpr zgY4{z7a4yE4_93AjVEP9WHi4~iN~8oV+OBXU=~*ieX`unm7;9RPmwL!w8<*Ggrb?* zkD5Yd(e3}`WIMI2JK@dOwk{l0*b0b-+DvKeJWtb4x6gQbUH=h7&yMzuv#?Zxjm;Xp zr`htmT?@$2SL$|ws2zIm(X=-SV_jT6{Ox+eCo5w~(#aMnwVu!JwWqhaSk{RXy}h0l z6%~a>^)q`Ld9LpJSBDn|z78@E&IaZAlB{;zCz0X@^hb?QcO#u|?(`^Rl)g@)EOEK$ zMt;A&iY4po58K$dgtvy3X;LU7E;#E#wPwJGTVo)uZJtY%r-=5e%9-Rn1`=c5sR z@rjMB^@~r|nF&$Iam%Jy=uvSQ4(GH_H@Y9(GOnWF#%G`6%p}4?$G?~J$HH#D2}?e7 z_Ki1;ec$p$cK2Rizun6C)M`+{GV=%xXSXw+<8*gFcFdhw~%xgyzcUZ}|uspNC2IS&j3LL{Oxc-cRaJT2sDxNyN zuy>Cs2jc=S2i_{VzB{)2w}FFhubRKwbJ~YlYArQw_e=@cTXVkyx@7MRV3w-eW`A{2;=0z2Q7;7x=ot2B^ zp-taEqh53ywCt2;R z4s9dK_G@6EGesZNw}sn$F466$(N)5yu*!_E{>FJvj=58QXt2fJ&SvzgOFcjZhZ9H? zeOViFdV0d`88l4)xwg%)mqWX#bN{~X zNmNcLk8U^LK1bX>UHm%2xilE)aW8P`_LeoiZWyfl`Td4uLfW1n30H16YtqDjeeVaP z0NPf0v%S6N9`tZ_b)ECR)?3k)CXMJ+x2PLAQjdQ71kpIlJ50c$pq9I_p@M3e z>`K1ru#g<@JsP`3?++c&UHH1efMx1gBVAl(dz}YJ!Xm{y{{#wYVytPat$Esf4+}1n z3W{!>YSDN8?<5Z%-fc8(-=0TbvWIvS30Ev0FV0{(WqkbAqQbg*mM-=C7wa_9Dq9cV zIE&`W$Zb|+U@wM`5p^8o_O9HXbabrLj!j;q(l6!g+l`?|V~@GyZ@K;odi?Ok>Gx@N zr}cKg?QbO|vEJ^Wvm)v3GFlnY+<4HQs!S1CM2I=#$Sp%-;~|p!9!iX)+UxiIopP;lyAAyX$c#4sgBv#q7fT`I4>UC z5k?kt$kEMko^RAH|I9l`;{%AgxbUq?aufJVJuOd{o$Xo2 zcsL?TFAO7>hy5ST))znv)%=Uoiv#G}-R2%Tf#h@9#6mbNJ$g*LRw^<`GLm9uP;y5d zbh()$5g#%DvIw_o(QLhDmb-F!!9<336`PJLEiQrXUoOcIA*}ObHqx z{9@@f0zD*Ke_lMvkfJ-qMu)B!ijeo(=itZqf$1i@lRex=(cJ+g8^shRKD+a2LgBzUa5+g_t!frA&i5y*O zK3H6053R-S#LEDEjUoOL8xCNIQ?IO}|BS_@%2ExuJ^tv}E0@dxV(PZ(1F)Au3G`R- zj+kdOWpU?>OWXz-L`%0+AQ|`2?+2(C%n6=E2rDqEpz?SbaFaWC=Ur*#I~zKT?t_^0 z1-{AU^X|3;RL;$Ajy1Th`uz1`0GlInMB!VBbkm2!hBV z_uCnN{~a5;Nn3qi#tVq~f_xC7CmuC3Fu0sIPv^YoS!=&5?A`A7pg8==Vwl4T8K=ow z(3g8U^KImwJ$tz0Ls5#|`lNNj3brm*G%|AV`#$x)7>Dh?cXu5^t_T$5YxJC~lb%u2 z|Js@VxJU}5RKZ}aXZ--TUnxCMeJ>u9Q6f^xdGyCU1VzZTT3Ur(bZoN;MqNV9P3Qk^ z<{lyqs8S19XwyzVEw_M?2&z)8ud@G08c|*>n4s2r&PAx6pm&HsP@pj$sTffz+2@@O zHHF+r-70H-1>CFOMLTC?EbTor6YH;JA@aJ_?{BRi5l`p)xzwi`l|uPT3|zP&UV3m) zQfd5~B9RWKFG-PK;1$Xmp36!FgM{9`bJ^{1EI8h=a@(*cyI@)eukWR!>=tfW@d2nd zaOKkQ>pa0Hl13Dlgo1zf=%KK<2G8p(gz0l-Mt2(!xdxNEXMQ`HfY<62`6er6loI5OJHn9YqwG0$vk5ho$RyBex^2h9F>BcWK zZG%>}YUVu7vZK0-e`a!dt+#6;*C+ORt zH}fX+!X1?^CJIPNdEaPSQ>nOzRrS-#EzJzF=r&#>1y!4w6tF_JIqF9wz5{3kN-RdS z#i_YpUm=5rRlN;692e)A7Ir~aouzH}RlUq!%8```lu3tQ`dL|+HQ(?}LV{5W+LE{` zO|7`hx4Cw}q*ayKKV2E5QFqHf2V!Dg-X=yB4IBbyJWkPh`-!=slu|LcJ>Qx4fScuL zRXLi3dE}r$krHajPNFEe=w4OPeKjpN}vijcD~8^RSPE5gs6u4YI=Nvo%4 z`C;QB-+s$E0|>LpC`YRL($WE_O*g!c^El#q!5w{kvLRGuO|RHFMhm9^=l?N9%l^}A zuZ4||XL^uosFS|QClnxvnu-&6-7n$+*b5whmFi17(kvwNABC{s=Jv^H4Gq+m;6I(A zpiwinvM>+Ho!KL&GfY1rG_XLNfVm@6r_G;1x2$M+3gMTaRJa*PSxFrPPo=fE0(V$~ zZg>G;+E|bo>1lxoaqgLAy9#HT>iHxJ!HYhGgq`V{5|s@u@Uii-`c@49=1HsQJmc~Y zKy9g^rR8jD#GxMta zqi_F2erVT2{gbFIa#_5Wg>~NK%ygE_1HQefTZ-O7tBK#>g6j5v=;`Qq?{2}PH9xiI zmtG)J>SSc}XKo(FiGbHPHrQl+%gM>v@o`zJjPzD19qH8Ov6vow(X4Uf;$|=2j_^H< zx=E;Czh36%6<0NCnSH!Xj7%}x%K1w_xlxUNz$vD zTQGXjqP{gyF1YGTs5F12Dz^`*59O3w`u`W7?th~7{m=Bb)JDol#&iZiZ13HrseRyP z4f*%7oqbltPrOxqOC!4Ysu*2q=AU5;^AketT>g|c`0obQ{}QEPP<`KNrH>~Xw%PXB zeuBI({NB6G0ht?j?08``vumE}(=0uGeSCa&n>8^Uk z@fjC(t6i!Sf!WR;dTSs2V_sB{=W;LHJX>ez!(O*kw6=>c?|vw)w7#)G#bV5#H*{+~<$@qnlA_QYeCU9nCPy zUZ<5_5Zd|Bwo~fzyWxX~>!Q+}EDDkZf4tCFrdZl#VJ>y4Z*zsosU&*k2Ht6TScBtoE~q`fJ? z;o^Dr92*$-qwEI z&{NI{s!#m(VWV!!?!2j;blmDMpA@*mX{P*I;ghF#d`8lqY5tQB{4~s8e5FY$ zyg18z*`zkE_o?0L)^;|W)5v+0{3UJjp(hLCRy1uf;pvp(amRn=xK8;JEPrUOtyP@W zZ`r^><0g0eT9EPf%=lx4mJ??u!fEGSdC!l}IFV;%elO=CD)NA+bMvR7-s^X85SJsXHDR zbT&6HJ<~btPTrEDt$r4^58oH4`NziVyoU&_2wzvQ`OLUcTjSfv2CVnEetj?fi|t!S z+HddN(Pq?-lAnf|U+yW_)|Ic+JvMOEuK4GZsusSwq<8P`-8rpR*RA-e7CW_X(9GH8m_9+^E_${ zQ~hRkoyj>d@$;FnV&sUyb!)d2erR3$A$Bak20LCOLMdnV`-q=?A?+#z1qyopA!|W^ zOUaVbpZ9iIZg<-D_k|vvwobk6?Q^51cCYr~YS$+}{jH-_LkkZLP1Cl|UT@nu+aPRe z>9e=}Dqi%zxphXV{Rs6Xh9}lXwN%zTf3w%8Q+b^x{4wozr>*VR^!Qk+6N`HaKHWwXTISnvEgG}!fFp<(5?!Gj08-)Wql zkdUzQYmK6&_H_(nEwXuuqG-j^jlG5hk9b%JGw$2qX$AmK6AkmPZ#Q@$^){lZBP zU-2~`ot%_A(Bv_!ToXU3w`yycwh!%`-`Zx6#$vdN!`@Z)7IGFb~bNOPDq_ey0vY!U|!=|dXU4#6e zLz3Ux4$Hmf(4tbe`qSDz-}cvnb9Lt0w2OHAHqNqhg6bhy$Jen>PKk?qb#9xh@?N3Q zbCa6`kICojG#S*sOZmmD!B(erc8C3yV{~$dvHad{N4t#^Eem=tPq=5iY-~#D{e`#m zRlnae#s1#T!uid{DNA13UTr^BMHhFPwZhVKQ>^38?#~}T-rO!fJYMsQJkRihy^IcB zztQ!Z|zVt>~I0R{U48he%Ulg z`7^S+>hrr@o10p&_(s$qS@fp%!BM}h3|fCd8xIF>8`?Xz0KAP?2!NbF}|byAo#$;MqM)0ij_B6 zyA%z*Woqx8@ay&dL%e(0-)dh+{ubT$ypetH*Yd9l{|-^K$H~9AC}XR6-=CupW#>mH z5&3HV8E$b+sk)G>hgxrnx0@?}3s2hQ)mC+<(T=oy@=YRK~ zMyjF$={A%f8aDY6IRbwE@BJxa)pBku+5x${U%@>hQnWi(3(ipb;D3fQnW*UeQxw`5 zUrzssd{y*R#5TOWyktBc^axnUAP-qDcy*`;e+@^MRVGb&u&tKBSt*=IYw!o9E}?6wz2f zNc>P19o!7cKssL5!t`&@5HzUF55YBv^svkPTw|Gy^vMV)h!7C!RcZDbs*g-U^wRTnko9;^!r%Z&Nbgjp^OY)I@(qrOruLLur3oxUWjk|13#NxocX1FH(!Mx|UH z4-@7`D)jF-*hvgC0hX47k>#ka@BX|p^&t&_#aA0S9;B7bnwQA=&FPL*_B+U5M$xP2 zz7-r;AKSSZg(4( z1h!%S;`;++*{Al}QA<;G*LJDsEHp}QyfExc5yMgcplG1{^_OFS(=^UCyxO=k8M@GF zl9T(St9pwS8&*8HoG&AQA(pJ`7_WNt`d?5jKtx67Y7ZC|vAPTyl|JQ~)yGGh?Z4@E zUfbvvBT+Q$usg_>4Hu!NTGRC7=mP3YU;pCc6OH=)_M!zvi?JL!rQVUhZ+VTe@EPx5 zl!b!2OjR&ptcbqq3n#w;;<-V$tX+)MHH2fy$y8Q9&O5*9M(KnCHc>V?3W8DV*ROYi zjM<|8wPUz&fMu9+tV8BsD%%o1b1TIIWW$z5>yL8{+#+xb4DVmp5@YGmY>jk-ihjew zg}pth-;?h|ky6xZ%}>XNg;fh2^LDOo}~HL)w}!|b>L<^tpbhgHv3z&mTK|Yxp_l% zhgYwo$#975J4bY|u{*?p8yohyS(pLLhvur)%K69CwMRKCCc`Kvd+Mt;tDk>R)#TYj z?Cl@O6mG1(i?GUVQNS}mNe$wN!>$Z^pS7C})k(>2?Q2D)`usnxz)iXc5UX6o-@3pJZQjgB!d; z3R&i*$uwD!DB`QI)O?^XC^t>i37|je)f;U$!ah94rO{?U;pN}XT{=odjFl7D_4)AL zz1AE|%?44x*)q&SWE~w^)Re2y*Jb`N)4U!+4c^a#{`d2WjMazGIJr;I8dp~qOfK!} zGH@6AEp#*uMJQZ`5C)>_`q`^?wIOgFKD@4ZRhiBeQ?bPPt+LA^S^Fi`M&O7DV>#2G zM9G|vs9zU%63uYP6f5Cd=8WzQ%=jo?ot*ifB z!=c%=YvV!s|8ub9ejD3f-64%HXV0RH!qb!AJ?I1q#RJq_vTAEg%t7D91(TBBY@fx+ zz=MW+U45r-QjlO-+)6qd%-i&|FwC3|(+zNFJf=0A#7S@l!hzXTCRWCv{~51l$~ z+D!h28~pXe+hzekP3!*oWb`38HYI0|FCLCsWvh&)s_WQ*u0V{*?X6uNEvs*Nkfx1a z>-~?V_HZMBSsl%U;gE24Gj~r6P4&fZh^H?H8?0}7R7NZ@)hnMicf;yyX*&?dXfSzD z%-!jWKd*9syzSDDX;?sYHPzG2L^Ue*2|%b6G&%Ya=m{wm)=6jpbfgnh-}Dvfu^hC! zv1U=#tFF`5SaBSErhxYCbufG4J$2+_eUK&iKq**|9 z{sENsU)yBWwE!o(z7%V_GSyq8Sy3#k-rRl$cc!0a)XQ+4=vw1k{FkdXWJ1EP=eH*j zi6C~AzK$6yBL|oAc=dzNIbGDx{AydI&}4EvMdKNZe^YIgJ#>7n)zR5u9%!^lMhHl` zbM;aUai>L2Jjh$<6e+Ks0bG3l`MTaXA0HDB)iEowOjy;{Z7K?#j4~!0Y*hVgeNOr3 zYY<^OyMJGqT6V4Lt=YXADdn5=L-C-nnj2~U^VgPfZii&7JLSykjS}sMEn2-%--pcz z$iJrRK-J0nEDvr0CPmeeG5cBf>YKS*|B5MdmhUfGmym=@Etb8{@vS~cCy%2U4eG3^ zwljk!ZrP8b*{!CEBeSJxwwmRp zu8ouWK}{9c#{u+E?J463>x=$hiCU3P(Wsxr0t19jcvV6kiewX;!8zkgqmH)c|Ja$>PM?7bcW%(r7>%% z((F?9ap|GD#JuRP3r80{LcK*o!Z5^4MLiy3HyY2jdpr=nkU2k4-xGhdRy{aBd(lP# za$Bm5L!7aa`cew?Ps@*&j!=)4`VRW<1fk3YvQRS<5T?ZI>?Y- zI+kj+a|p5AQ}tQzrxTS3vu}L|>|2lMfQ;{j3@RcyvnJQXrqY($xw*FJ9BZl`jFJj$ zcNp&x`swc=*`J36+GcBZWvIbINW{~+$Bsry^YpVj_OWV6B2q{qlX;%9$h@GoYM+|< z(#Y_^q~#z{1Vag~QDP)NHZY6CdQlb!RmZ{E2xng)B=Su&BS`r>0x6Q#+> z5WD6d7!q@d1Ksw047&QVH>g}mM=JF8od;X2CnBY&>@|6^HF5^k*Bujz$cyAuwc2Wn z7Hxg{yBhQzUIceSYMGR&#<;lL*;docf78rfB7-Y!HRpWyEWND1Pqohz9C^}k6_jnY z0d|U^lMnjgk9M{lgwTB-<-VFuA)rN=4X z?9_w3$Fc<|dplWGeO@;spu^*!u|&ee2kdH{nmQg5@?RD2Lcw@bgFU9o<+e-|4Q;>Y zUb8XR`y=PX9;>0QM%e8C(ZLLw2Jsj9DY_2P*5S&_?v|h*xFl5Q4WdmgkSRe%Htx&Q zWsGz|YD_r)F!hxk<|X^~8*U^@5k!y2Ti4U#S{bm$o0EtUc#76K9w%tXpzC!|$t(*I zIO7R%hB2F8Kcvsx$`Qt7eayb(PH#s$9eoDXYbxyeV+|dQR_{;IPVLIJIh*13D7)%o zcJ~ARHHjMX#Xfs_w)0SUFp*iI|6cl7x6eApl@?W0$}GdiO3f*6dNN|in_e^GVb3#u z+fl}s#2N35EP}Ifw!Sy>GvD`h59 zwn}6t3Mrx_Ss_YBl$p_>q7;>p5Xw$cq-2jo*)!w)obLO6|L^-A?{PfG^E~(SxUTCr z&hvYI$7eJkL#uxC6um?6<@XXq8>Yvi+GCQhF$yM#Af)9%;@%tIFa9REXJYflysW=5 zgMgi_CdN?%5^|m#q?2F;!m&Z?9@0W0UjfDr(L<$?45Fy_An0V6%0vH^%Fjd~Kp;oI zo9!P!;SZ4)m@cP*AfY`giKHC#fbhot6OD%deA3>*fxvXI_^@C-=laddYVwH9(&=w6 zG$7gtC0pdxCJgmO))J>M{XyE*07(CFyUSZ>;e)&Q&`8Sy(MW|Ffg4+T``h+V&K!4ANH9m&^lL^4^hFFqdQf3gfqQ^V-=W7(pPspC-OL(}mgI^nYgzIq)S&B(tC6x7<%eb^x1a?hn=x}6Ra z72Kjqj0#j-Fu#R59tZ(E5`S0pV^@eAJT0=s)(^K&PU2l=-~?v{)Nw z#`|v}K%$OP%S{clWW(CSF#A)2{G}W<1ZnR{BmHZ)BnRye9GkgpWKbo!>zR47M#3%s zpKtnJld~hM35y>`#TecJt@H%BF3^<_s)=bFLO8Aqxf+UtkJwu-U^~#$ksP5#Dz0mr z-QmjOGh1_~<1$Yist`YRLTmf2G`k0y6Pu@JCPi4IdA6!Tf?%!b#qL`S%!0tp>D$^0 zDQg0WMF%lccqYP|DY~v$1l;u`LZ5!L~KnnT!|-1{?f!lKs<2zpyu?G zI4qNElSP_72rLMIBPSX0Y)hr>^VBPDwCdXRvp9FvMpg98H!s|9u(5zt^H%&=K!r!0Vwv^13Zu_kZ0pu8RST(7{B$rUa6iHqpmzdTA9%#z zZ)?-)H?uLpu*3jgNW{gVI=JElWmacnfU}X_#~VmBRUW1Eb;U(T3q5Qns!X$t9~r(7Np^`z zukgQFakp)1qd&cad@$RTcvbpg{rbxXjAnBRrcsESrkv0+Bqi12Ft`cwX1Ce{lMSkx? z^FlrLEx4jt=`EvysdttD^@rb zCz2$h4j~v3q?@9IW-<}|B67{v)_zL3q?a4Ix#iM_mxxu|Jj8R*IoX;`;61qW7HIuRVcsZU4H3Yp2RKLUdIR9r@e0Jo_|ukVq?3=eL<|~msrt! zBEqdPa|8RYJ&Oh`66vQ7%`y`hJ_L7~DjNn6fL)z}O$ia?K-Vu>lMafS|7JuWiwMzl zsmK3>rh1ulUNtvtYu0Ew$8H^c+ROQheYk*#PDry&?v^v*mnKe=U23g!=%lmiTa5w{ zm8q{;y&}2YbPq(`58;A0u2)y(jKT&8|DKKwz&f_NO2*|Vt}4c5{EJ~4(OE3+BIGn^ z98md!)zs98*vzzt0(Rg|W7%~w&_2SsgDpn{W7LY2d4u;Az@t=gEHhn1Aair~<&hgt z-|^ZX2;y9Ny*puUUv6bal)%eF0q>HNF6i?crHNjMKGubiKJWcI+i6bOcRbY6R)v$Xy5-FKu7X=Ao`glP8tgD_u44A<}n#l98`|r}{l{r<;!Mz`!}cH%Xk!&mUplgR{H zxFALpkbZEN1O!EJEs&ShN75xo7Lne`k@)wk^Y4cZHec$`(!72B^(~p|%$%$fwWq?; zI#wP?pT3I~E3sRjb?k=7&l9^HJt|)wcdamWy{;cM`=B|iQ23y;a;f&pH<35(wYDl2 z@;^FQFt6=TkMV$J41^~nq(p;>JHg^v&kRSN_e9SJtT=5*u+|k<&8hBWg5DKT-+*0| z9#4^)UEr{N0d%7suV!!4Sc4VJCZLq z?Tn#HldDAf@bh^Q*{@&v?yNij=6$Rur`3i~}5xnEJh zHF7>9;`9-Okv@Z&daV%FCY!@s5ti5X|GCNUmAow|_ofPC$mGFf9z#o}9ZeBkv6m|c zpUnM-1$h1GwujEs$G3WGT{(L#&s7<{7<F}};#c>26A_0l} z21)?9M;NS-NF$zZ^tnv`=8K^J6?!R#reI?oS^DM*d%wG${{D&TT{m~Es-4)u6l0oY zT^pN*aMJzsjlo2Eu7rTKFl)5#$KApS{p;_fpV}lK)13CXVX!>BP)RT@PIrE6jh0H@ z+RBWG?O8|WeXjIoxVF(391@RlfszIk4A-hf=R?*+GwQlNYzN|G&NLJic_ZI(<2Fsf z`E_y6CgK_&5s@CDJ`mV1<(KGwF3~Lcvw)X~{eg<=+n<6gwc@`%4(c3yqC7V0kxeZ$ zkizXB`t$4iiK^JWn>K7={rvT9l(%d+If7pGW+_gh=I>5&)i@psOcFQ%CuFYNXZkZB{Zzu_`OPmg z`9&1IqvHcI-vO)`3?yY*JtBClieUOh(rnDK;N($mlf_&q;EWL$Rt&b53pnKTbpGNt z{=VD;tai0eqbd?4N8gq7+}{31O*V~t9AcCAU@ zUV0UZAwO4|Pthy;)m;}WcnD-aO*J?sKK?USG4XJ~+Caop$yG(m3)0sg;ZD~z`aEI} z_S9C^kE(-eS_vM86Y&?BpIZi6Mq4}CRwdN)7{1#Oc{I!TRkd*pmk8tZ`*mX@`46ky zkLTEkJpY5^e6C<^u58TK#f zEg+H9Gc()dV?rhs(5tlvPlcU}OMrymnUwKnjT`6R@I=TPy$UXOZ%ea$Re94ySbd&8 z_wkuqX(Q{6>g6SxOc=G9wssxg>%G#lHX*I6XL)4akY3Zdo{DF()Dz3xUbo(y{CSMQ zXH9NjN*pwalxddEFl+%$A%UkOX{r#zJtB9Ch0VEIVN%q;s#_nt1yYD0FDDBo1uuEx zMb!oO?15dYB#ca%FGdU6`=*~d;k^D;rRlk=YY$|EOXcnlXi7l>C_Ow?FLBzb{IKU6 z{bPmqO7j#Wq#n4rZ`$pv5Kg%9a{nRMaw&t+P^tf|l%XEwO;}w03O9gAs3^1p0d}hn+eJOlmK07kA zjkhWDmvyv}CbxFM+r4tx{ZZt_pqc|<7KN{bg2Gcs*Bs%M-g^BYD#jz2-=jf^w%>}b zwdntX?rsN*iS&|vrCGGM-J|CVpA;DEzLhz|yz6?#wSsHbuc{KhZ@cv8QtSKWLLclp zN*g9Oy>_y?K5HAg&ui5SLGoHmzGPS2tiE~-NU4Gt+EDvsn&q#pNKSpz4Ofna)BnnH0|&(FO^R9mN2iJ-M?h`cWgUv zWN@up_~_=zfy2%h9mAyl&E@v<7RuO}T^GpRuQ6J1_XT3Fx?Y-Qh_z?~b?3;Rh1*_! zFV|0WjD$r|$ zELS5i7{dNZwD&byPf4zAW?(UPf1qiVMD;5+ch~b=ycN zi~lfhYmRSA@+rk-_I5Eh*$bb37HADeo}f9QDq0}C#5~x;anvk~w`IU9WrPHkw=_}l?O6B)?F*7K1fskT&UV5;g z@4n2UmeoBMq*E7W+ushyLhRkZYo@61wA+DhyP6F z)c%%qLl=y=kx}V4oPaklLghb=>01@ne37-`P)vj%2BbIq^{I@Odt&#zIfl&{iC?y9 zOrKg+EN-nGEpVy9L?F^!?80yMrmWtI_^@PM3;pDZb4XlMBHx8>J=J1(LThW3rNlY9 zcY)_Fd2UA?iU0+2gB|oq7?{;iFw~)Qxq^Pfc2-8XdL2YPq3h(dgJZ9$g~&FzDnRl` z#qwL&8Z`d&&RQKkZdw>cuh5j)TP`jv7f`Y7pw-iXTrFe{>7~281Z{_J4V%Uu|2h<~ zu*22<05b~#R)F}xqRK|Z>PYHMHOUMQXC@UmjS6mRa9wdNBsi17MI)V2ahi1g!4eVH z&*dQt_v&jG6i4p#@r8!Us7eIt&9^%)Rm<%wy^5aSS`{{6r(9i!jr<0*rBd@1|;5>03dn z$w`7CXBtX}S7TwG$P@}+VfDW2ktzF+Ns~jIX%*I=NErlh<0!sSgdPL*WE<+Kik>b|KqTN4W2|}8*Her0ds0Qg?@Zg;h>9LT7S)$o$2=bw zeeHWF+kjIZGn>mpiS_mMFQK1}T$B`?7(aCSY5T0(dIVh0P|Ul4aU-gRE9iGVhRzJI zv|t4xRo!FtONR*d4^EC2z^Y|o``JH!YOl>AE5iAXxeNI4Y*{L#E|ovby?I~R61R-k zf8=mTdkz%Vf>H$W47BQqetAQQ$+C!w`zV%3TCT>1nd~|CO`8O%)j9v~n84533;-XJ zhG5~7yBloP`rGyUqIyC7CF|N4p@=X01OvCU9OsbqoEm>9vIXYBWvSYj&1sT;5PlMK z`@Gk$jRu`o;K(Lw=g4tTGRyxR$YSt$1`V@1(2XK*-5L)vFMY?4tHNPINUO=Zf#_wG zdX0vT*`@dIi!qHsWy?&x`~GK(ZC8J2$Q>pq^SU4adHzwfeSVafe-hP0D=QWBqB^hq z<=Y0OtP>|@xmJ?sXpb$0pMw<+(ZcoeD#YYv=kl=@_hJlkFy;_NDm84GTy#HQz4hjq zHgC?{RTA5@Rg_CPTBa1&#RrEx5<}7f@?=4qR|{Ihu-d^G2RuPY&2S6N(x;;dOJ?uP zYGCfA;D%SwGv9;yK05v%QD0yN%{6%u>fj__!r*7y26&H7$)aQUe)X)`?NSruDk~V6 zw~9Nf*tX7PKit)Vg<$gOg#fw&Achj#2c)CK$7WV19QNzS9CQ77iU*o(6TkfYDXh$M zS5sTt4!20?VOYQ&?k_%COAwQEOr3h`#9<~D;Xlj5t~e4fTk<2bSF-%s*A+{dZD-3l zkV~t-d(Iw^3<`8-rnJm{(94Md0`?N@tei^bR)8}My52#Wr6eqgiQW+(RW%(Gmy;Np z5l%2D4b44a(b2+qcZ3tG2SkWY@Bhw&HXn4R^WnK0|9#r4i(8I;T^XdPlG2{$*&Xma z0*e7qONkILDCU?1pWP9Eq4S1J=0(+L9Pg%x<~&r@7Znv6q-%!hDw$k;?;O28h+>-P z-EjFR^OoAKoGz2{{3*3m?Qd84sW3|$Wof?lVkWzXb3%+u?{*F|VQK+F_eA8}9`tXa z3yiirX3a3Vz$Pji7qHA~ashJ|c#Y9{>OI&?5s4cis;WQObz~vpICYvH(8p&%szWb2 zCB#=Hu(p@u=cli44Xw4dM+oeQQlcG+n7hONgG2uNH&E700K70*Sl;Mx1W+T)wzgpk zn~;!@^CKK1iY8RR3THyZFX0&9_)^W~N9&XaQ7OWr!B7c)aUH+LU;l7K^LO!=Rjm&I9v*XAtO*~x4o7@+|S1OUh#e263)M9~6!zC=t!@}l;{z(ono z^zU!0snhSJ^4q=kC;vP;`0?vk*$4g0#ZGd)&Z6rk-E)mc=rjo$v#(0<>fbe(<-aRWZ`7rtXBv(*puwg1(vGTUw z_ALAL;TGStIPqI=qwe*%!J=!^tL415Ha0}84Vg6#*pQ|^B>?#JPn;0IYhzq?g^bA8 zO~!HXo@bz^!@++LKn-NzhLA?rEHsO#*o^ZBx9&WG)hWnSiCaTf@^K|!bA|8UHPM8dia26=oQaNrxa* z$6ZPI`NqoTYO%cGK%b63g5O_LTp(Y)UBmf>`VPE#EHwt?;o!X!QsY%AN;7%mMsAKJEWq} zmKNPuqC7Pi=Qpo?$9+CcE_*aeFN=ROUp{S9E9+tI#{^XA6%X%JB5yIa0a#bP$${-z zO?x_b=X7*J&#&A@B5*g!Mj~_+Hb%T7lvhN8cxzqi4k;D7#DLxNig)JcmW(9ItMTN- zr)jX1?Y`S{GAk?Vp4}Y{$T@8CnsvH7U1fg6-Q6XfPE<^+x9JLVQdU+3jTSZQSvcQq zKEDqUJ@iT3#Rv_V=CezL*jQCGpHvvY+C4Ypq|0E|O%(>;>pdK@Nl6!k@iwr(e@RF) z?Zw$OgBfH7F*_2C+Ilxs=2L_1`!v!RqwhE(&h{CGGUo`FeaCnnGLc&`F%>J`3s|n= zRp`t}F(;>cQ?@DDqfO1$zAL3Y+qxgJ^X3D)argY`xC(3HU->krgHc2O!i5W}PuCoK z4rycp!r+tB*wiEf4gw03Xg7I)9331qv1{T@OlB{`(sfi5eb0i{ANT6! z#AwSzqbH|&9?F@8ma&Y-?7pMD2*ZB6#xn^n6>6VD+%fU>xWq+AieTM9BW~}_Z^!H*IsfeICTo5Z#ag;V}0Q8`#L{Pk3@68L>1 z_}M-B)!C;?E}$k|OI4VErz}>#kN@{Lfi};4Yb;0sFTG}J@PaI--thj=qcYg_=%TVP z3^4l|LNC zKGnHqUA*i;9?}hOEqaT41nLZm8}DkScf{2Y{UuMxNBj!laD*Fr+(c`Iiyk8{Z56>S z5L~O?f?TvTf<>{_>_>aK@z;t`*|zeQrMZ(S*VSr81BNB!rt~20Nan8Odq}hutRK6~ znGb0L2b;BYvdfEl?a!QPM0I;_MhXDoDy!#bC7j;6t>#V9ESGsYyffX%XzvIv*A)a06D8W@R-_mA30vxh{ zy|g0#=CUadb~ZK~r+Ysakc|Avv25@rcvYwTJnpgYp1S7SqD)$+;yYYdo24Xk3=dX}CnvgYZe=r9wLeO1iU(GPwDh&~0 z+e)vn}=u*J7dNw0FEN5n% z>E7lb5Xjb39w%m7r$4P8vQ>O-Q~eJ`x5mZ*rl`oSiDfkU@7mLYY@0SU z;0z`u8dj&sjve7`V)ZaBO+xP*%kwS3$N%&MXqsHVCb)_{&*e=$4p#Wyef9WE<|Zeo3S~Fq??-L#m#_Z>Ux}SwBGQx$K0iLBcZiF z2Md2aPCKe7TSH*nX=zeGj{z?E3;aWa`Q5;xy@0|L9`iH)KB2F`WdU|}fL6q+0qLZ? zQ}=MnLvngRk_oF*Yrn*?uJY4@*W7H_GE)r84_~~#c`t&Eh~&;zi>D}_K`n^Cva!uY z4uj_mtnn&mg6#q9I0 zit}h7JpxKY1n1DHA1>e*Xanxeut^YO0^@wQ=VWEVT5EVA@y+hgkY5S|g$prt1<71K zeo9ncUO$HYv0LM6EDXLs@0|KN%wBdQE5~uR%F5QsPDr}EMk7x0^tXD2)7s8xPQ?-V z;`PUwq?bLXmZmJF88fS_q|#KZUVNCDwTv=ff97j!U31K2KX+n8QFU|eo9b%Yf-0`K z=DuQJ0Z|{pAX91o;C^@bi4k{fle0ye2{3QlHpw4y#W2Xjlsb+jaB^X_8bkCJ{+f)n z^z*Z+^t(hkC;N6nmXc+ZHS6d$#9{((cY!7&oNF9EC6+j5_fHlsydmd#K$lo2B+;7YL zhXvTW)wODSwlE)`)u+TxoE}83ZxIIp`^rP**58|(tCudD^4{3k0o*ROgwqI;Aq%TW znwLZVWS9=OqKJqF_*x8H7R31?rq)A^z;Gck=ppfLlo%~Xc};I1x{M!z@Vg?XlhIg3 zg~%a<)Fiw6Z8q58dY`@5F5F%_MN?L~DcRnsQvTDz;vi;Ed%<0^O}MBACnAN5A<*rd z19IduWT##yy|MfYx*R-^tCudFDgpukDBM1?Y_XJ{D=Jh?#*FWe!e4D?pu2eIxU-3D zdws9PT+*&;CWp8E0_i*HRo^ac4?bP~6ML|6( z@&qN0Q!T<5S|t}wCS()U#q)?!5fpN0LXZv0vfqAb6_j#@MOEE5t< zU$&r<{PpU)qXC%C_Z7?Vz{iQL#lmdufwI&yJMYt8 z8gJzZ#s1Mz9bTr@kXOx{oA^Es2|#-Y7b-M`zkm!Gk$qbn5<+w*cw2C(d0tulD5N8fdd%b5>zP7Z8W`D1F2aeDJ$j8AtDPPHw z%4@fgj#?oVa{b1LoVu`IG%M2d#d42OjgTJUtB_$5EzGfd+;jU8E7v?cZks2p#Ot95 zqzue_;`d;sPsK-l^YA?9%y8SOVU1O$;@9*e+mF4{Bs&J<@nk3*Xn2L3>;2G2s2H9T zS&2)lCAHvoEbPba=ZYpovE)}1!535Rdt(61P1NL7ZMz;E{24=t$H2J3fP`3*Ma**| z{>-F$%?J^(PJL)ZM{=cM0FNEBtB>LzM&4TWnSn9Ui|@r)RE0erYBNASMBen{JYfnq;7&5X9)#x((~PG*v%0>rKxm^|)q`m|K{hpXNjr#s37yxwfUnu_*q z?EJjHf4wi2j>R@~zgg@2r%D&S*$m(uz%?`fWS}Ge01iGHULMG+K($6Dt_^|7sQSLK z@6W;Q8sg4+`tGICK5m#ZsQuI%jcQK62W4K?}bc0o#+AvdU{MB(!6)RY?(!y=M~6NrK$ zd?t-yK=2GqJi)o)<;$0klZlSvOkF6<+kR$s5?D3-C1jJm6Qf=I!cKML$-4x^}mi@!)JigDi_$j+sxY_wnew(?H4x}T4JGca3oULGIG6Y`khOy@4OE(flk zDE$)7FKG+kSDYsU9l(UJO3_9&8Qma_x_!RvHwTDtvkv!zPThNJGdp0JsJOg--;NkG z>Oi{E!J3)538W&P9vZ&s3)6`Ub&9hkir`oG@h@O$(9f^ixbf6Cj{2QsNo!VJoQ~w| z<)HEf!d2VG8UqV-lL^*?Fk)b&DKxhWtb%dwg<j654#jkJA+L%q^T z4+eFnTdiU}+Avp3-majVEwA1ktWO>GEDoaBhZZcwK{+DPnZI=BGfznqoyL zh`N?>T{sD!6*A~{1x)ASo&=4#k@KkZFvcXc|3_@^86k5uvVyq#motNy<0s-KFM8vZ zgJ7VA@Z_82bNW;|FAZ>6dKD&jU0(Rx3U988`-%ls-Jj5ndg9vOK)}O*GTa2SF`6-$ z=8K4y9DcjzW|OPcJy5dQsme`EiL-GguiV!|gj z@7ZI5^~*{gl+uodmxh1pJblIK$Vb7b9=}3mg#PlPVhI*I1U>cI+ckUW=zU^RuOrYi z2!$Tw-yT=~Hi|iP&94JLG9=H>oZhwkTbHYj$>?z`O|AH}@oD>-+S*<}-k${?^U~bqUe@_AVWl6aqR`?wLEX6wfF#5R*qjvnCQ4#NG>&tW&6p z2=imfRCv=rF_%v`w``dtHlbBdiz=IfxYI;=qE~#me6!Hx*~HHVqe2UzQd{)e@eARS z>g_@2Sm*zE3Ax*Q%*#Q=#7HqPNd^{n8lMp5iQ?{}_9)6`^AU<7Zi2kqRWhfOXfsb} z1&Xz$VVoO6s+`($TFq@S7=Qq>tR;0LTGca1gC7!7Er*Qbp@RokCQ}sNv#T&{ZJ-s8 zA#!!)H!IU3s$Cx(`xCx0#qEjahJ6naKVKCL-#GKr-u!PYvE~Pi5z*4W9EgO1iXU+WQ^t?p zgFgMA4?IoYiLevNBlxy-*JwKTeHuOYHk9$?R8F|qvk~|&X6n!m@ZK1CE$AIYcWU^5 zRPA4W&e>VkvPeBFCgu_BPE1J9HM+3UgK6JTEsVi3+xVT9A<82o)sTrF^Gb*88Io;~<~1tgbq^g&dgXE}vaXB#)OMf8F)s-E@ald}n`Wr!8IrotKy8Gh@lDaRnZ>O7V7soF)45@8L%6hY#QP1kyv5w@6b zQqe!x%W>*EU&eP0+TfM(D-^+qcUE=(Z$vKo94&#Q&cZoinD@pV&p4izD~-RyI%jvB z%eORof^tcdq=?AEvd9{PE{O1A^W?y=*4+uN?j#ov@`r%f| zx^CS&jU}3baNQ#w52R&XB96p}x-^BEgM)*$aT{69x*nnlk)!%6m1j4mT&Ev`O9JcV z_Lb%zTjzeX!s5au5gqPrX^4o-*a=v|s!;`M@=#G~*wzkXP-Swn+Ra!jG7pb9xdWQD$wU_Wp!|NC z)!vO1AC%r|1jbJ)2}tvr9ocGrSp4PDz2qJGfw znb}^&4APmv$eNF)xwr)xd_TGkDr3>_m0Pm&#_A8qfDjl0iDPmBhS|R$+k6Po$fs!V zpDz#2Pq@&qHo#fLCQq2cQc+b^Pq0{*ySJLxq3~V7;8{Xms!|yH=}V?&ld2D;t+e8I zAK+!Mkb}+cVr>RJaC5Zu80Zs^uUh=m5lxf2qh;TDFAjY0F&GJ66Wj69c-wjef~k5j zG1yi>r62kCkMrM8L*AH=b&6?m?I326&0Nfc;N&qv6tF zt*$@Cu$b@rMvv-W=iH#9PhG-x?+Qgh6E-671)(EABjZf#6+RZ9pcO?@Xr*TyE1v7A zWRyJ$8eNrg@eKyLCif`{H(?RoU#HIf{oVSb-NvZS4f)4|BgS1je;sCWP=svi{@!hn#cP{z5<4@2ua*~0G?R!C+bOQHxK zguFjdHo-!(L(&TyL?KoWVKpi-;u!KL+fT*xe5;_!0s+WRRfztHHp>zLOkNaWqn7WDHiELvPa!clue4|cv; zF4b~LS8m8)U(M0S(eYod#bh05_-Sphi3Op#O@~a>NQsS!)qOzl9zs7&_v|`FP27GP z*QRWgt97MK{Oo&%#I98yo&8hZzKZd>mef1m9Cgu3DVG3{=?9ZBJ_0BEV|&Tf@o)AS zm=1aCE?xnprJw7|y`Ta)t+6i}%NMl5>o>gF?VMw5>C{K}H&f^X*N(&0P`{hEd4ANI zEdX70VD}zCUz`ZzS*WlruDqe-?vGCM(VV@Zr+&5-Zk4#)zPnr8_GNL0EyEFB$)=gN zsPCVOQ4B`Ah4+}ClKujn`+s{U;TRF znIFz<31Rzq^Ops$rUz>C-<-vLoB(V0Enl;#>!54kiWCSi`qPGXs(WRjx0>hN)q8D! zjF)Sd_#UTMt>)Ly4ZUbS-ea_8FE0aaKan?rd7Sx=@E6aYhwG{^EN-*tcopf7g1t&{ zPe0G=GgsseI_!_gGG^8|H#ahC!_I~Lhk6J@cj5?5W-H_+q@`Wg_2pdbXjzO@wRf-H zC3fNGfgcNLL#4Y6)mQWDdt6{SzjIwNj%&#K03>Um93}w!ERs5h69-%17)sbiII(` z5>D5Tj*jNCQKHo#c1|3=kqBxNp982KqB>RMYd zV$QWIIKJR#Y*jnXcmu9WAj@o^Q0o87mtZtPT(=2r7y!e!(MO-%py`utM78m1blb@Uwvmjk2&{$?AJ}(A1L&!&S&E?}y*k%2X5B;{KuXLS=ikgi-q7Y<vs~+Kco@pzy+SO=Iz(qKrnC1o7T@Iv}7^gGs00l2J*%x~Sk5b(Kzg)}qLwp^1JW!7lrsMhQ zsJSMeTa8MmnTxuO2=Os^he^X=U4FQfg)Dy{V>EaSP{jK&F8&n;e<~F33#bTA!HIyd z$q=all-w_D0D%+i>LMM|xTK@Z2mYH`fwn;)V+1COksbBD4vcMCQP4`3bq>49J|eFN zY!>>WzZ)Xr&J-9Cn z!w{=^Vc#f9hUYLy1$-|32A#J(7Q7cc@$mY-&CxnZFxz^V(j~{a8s3{% zSXM#~qNr=!9kjF5lB;X_VVMHxh5_bvnB7p9Qxy16p5v^wgFYI{HFU(S9=DajdOjT! zZ88mEpm=d`a~nb)4Jad`x`as^q(@a0wq>8%>9(n0h91Dp zKtpgzmhA+if~0HS(_@p91mBC{3!F_1(RoCBZpAW+f-ialw_rKZ_vrzeX&(VbqIUC> z?k4;$gOj%SVTLX(v>vBL4*(>@rj5*E(SpOOj#apvhcHL(LKS%l#P;CS3Q!9Hz^P2r zkjOAS)^dMeRz^Co^wiaWAvQoviO>=Ou!JL<9sw6Gp>XrzrDI7L0*U}|3ehVP9_&ns zbNqx}ly8sQV(zc>(J9vik4N9t^(7F>kk}#)_oO6VP4V!?u}qwkW2H~WqWOy}rFPdg zL+4WY4Gjoz49I+s?t^5MXJrOJLowAr+~&qd6UAumt8h7}66zCfpN% z@j$+4i4W#=hV1sWGb)A>7D?PGZ)-b;f1=q;HU-XIC`Az`Wpu%c=}>=e+Vm8Ahs+mP zSXcl>Trth10ovPmpN^N@!;n*ehY^^l?{ZwpPc|+tqI^Y!7$CQW8-c0ujqiq(qDz6- zu6;t+iHL!Kn1pGozr%XeTu`t){qeHkzwJ#W@lm%ugj5JlWeWPG=#o|1WSv4sPg7*6 zx8hDb9OCLmOo$1te_~=HtO{P>AuH*4{UK7sTLOF`xFvu!;#R^jtH85{D2S3QWk?<8 zsVjP;_89iV*X#>cTsh|@C^Dc)?fZ+UAt7IQ=f4W!bT)&mIyu(^L^T5uRZvhc62NDy zDLju0C#yQL{y z64Hyvp!JdO;l1!jRjqqb_8QtZD0-04f&Obh`R9j8HC9&9Rl?eWQ3)|uA-fc9#+s89 zC4C%(h*Lx`2iRZ&oah{8_~F!ob#VZN!QH zJ=H&Fs61UT$Ff5ZghC8}UC?P-8G9UK;+X+k#k8TJwr>~07XxA&%UP^W*jEAk0tBBJ zM5Qn;0z&u3S&Cmeakw_kJA{)X&u#cF8BNX{Cyr<4b6?Dt{>WV{`zg_zF&QK08d3lP z7XW7gp?a&JU;w`2K2A@lTM5g^7y>?mMVunP9@I@BN|yfEg?|LBb z`iR1Z_^|=5OZFWAJJ)X95a6UJi=qC64Oas(dqZy=|8?2t{;KNg&pji+IUG7wM!0t5yID;3tQ-fpIea|5S;tohm1ZIRF^%YNGe_ZoH)Bmsl1nY*(SqkRD7>*zTcd0Zxh|^({#}MSk zdTXe>3j1Z5DMg>pz5YR*iva3)irqyF(}6_>7|cO!36C%)hG`tR13&jt8?>m zq)0M)(vbAwTmQK8+xE*u(2B0dOXl7#m!Dw-_5$Jqa(E&Kx7s`D_)FtkfJ@>LR@%KJ zfx$8RyI8F}pfNLW)__tu-g{PXyBi;0O-vAZ$2>JBSoSj|`Lj zM)2ej%RS^W*Ku(@A==Ws!=7^ZNhrFU3&*^WVj~TN7+4F4B?M9oVOabJxtoWo>grG_ zItt_igu^~#q<(p150M0hN(=Ye7_$P87}8dtFht;-fi!^Gk6@_5KHIp;J83PP($PjF zeOY)#=6Oty+?SugN+UhOfX}we7DG5y1u_O?QNpE*oT)gl5WgR!q-2t>2m{9tV9QgG z=^`tzyu4h4RjXHnAEb?bh2N5* zF`Me>WRe{KtpQjamSj#(86hwzOy<`5H?Of-+;cpovYe|yE_)0lE5TSpy##_*IGEIB zDVjiso1^pqCM zm&S*W9u-E2fvRFP=)_d9e#j0BE8Brgj7w1AvUs!UCdwuPlYefZBo=?Lo@a zSwvc_3KGLG)j?W;f58G=TlOEV`s5B6|9s1HO#?9NF|1qAqIv|%8Wv!Yb-vk=K(e@| z7zp5w;L%`4b{Ljc$iDF@-15HvzNH8uAL|Z08r;qyC#UE56M%6LqbT&O|0LalcS_nn zqCY^EIcD^Pj0*S{97O$=fOJ9bHrWa+QBXtb667zT&7Fcg7^+SvQi|!IABuSFty|aH znnC6xu=^vE1>6g6J2EFn#>j}6FwI|R5I9>=j3Sj{@Daa)mh{XNkMOs)}s}h|ooGiCs z!-0zgRfx>L&Jt~NY$cvUCV4IzKn9SkoT!c9Ca{mt&S73nl#wY)4}bRc=>Y*pv?gFT zofcPDT3U+K%jBOaHzj)Fpe7C+;EZ7iDs~EuS+e@JY|(d<<+l9iz45+9%7GLV%1Q{u zZ}K+Qpx1D%KNd=h*R=$ptRoLzUuLTnw+lB^5rIyh_nr(KVQeGqpF z1wOp@Hq*sv1ckO1(`Ew5#K9{9b4k1`q_v1CWCbGI0AvZm)ToLkgyQP98NUd`Xa8-Z z_-sEM1vl$m~2-;b@a4| zWD2T`{(oqf{E?In=UgCLlYnC)D+B$7|JH8Np~Z$Mg@I5H9z*{X?-^=>cBfC{u)TwP zQtJ1JLfQ1Itwk;8Hv-Q$%t-+#1NvctYx7bj82VljlUzXOv-xV|dq+P?rVXj-Fop z!M~3u8tK*L^gjnSH-mmZ(n*?~Hydg>6ePF`@csA@E|Hrc>&3=k zX`^cNI@HLND}QsS?|hrLSjQww7&w5aFi4r8HR1_MO6!<76-1WJ4N=qNXJ||8Eq>YNg9{Cs!ppmMx-oz*ZV04lW z<7h#jfTY!bIp~LS5fS038qPD6fawRtbHXY0y5}LBSH_s7k)9C_3D622VwVD!jx`bQ zEz*N5?d#WvAZ+eaSGPx&hDDF2SGo*C8_TRXi5`BsytBtifl}a+3puW*$S<+{HL;mM zr@L9-*JZ8w94mpa`BGBU@N0xt27OE-O}8976Y+&A4O4O8)Z=dUh6Dxa;r~SJkOa^S zKZ^|R5eQhQsN&;Aq_L_<3kB#3gwdOpYzQ;xFkwA;*J9+4LD@f{$6#I#6A7tvJ(?(t zeqmL9Cc~Na>r((aN6SI`Giw$qL3nB+eIx!P8iVQb-SYtyg%ILW0TloSpUHV`B^W~} zV)xKZ#**9EBq>>2U~5ZLu4Csc5q*QSQyxIt0r3LXdAi!h%s!Inh= z;J2i03G!)`qQ71fJ5R7uX8EDk1@-eChkbB-9ftHX0sj)CWT4(q9DhQ!D&%sl$`Z^E zEKPDg;Q2qee_wd9nwa&+J*L4af(N;r_oEk>5JK#;H8SG|RthG4Br78MpnJu*1lWHO{A zwKO&1!x6}$xDT2fB=f$f9!ivzQOW7)>)#|jjpbBjfboEV=EbCu&f+m*`0}pR_ae6c z|2B*%lF929*MebSf&dHO)CTZMyPR_)aZD~2^(v}hdjlG_0w4@Z^cDhU0oy_4S2The zNtj8K6^)KVNK{b&z+rY9(6;+_EXB4agnKwl8^D1Zr!iE#4HqjZB_Ei`(>2=T*2OB;h!UpGTImSYI8!TQe>gz`btnokl%g7rbHt(Wg%GqziuCMpfp?C!L z-Hk9<-HT_10)wD04`Z|7=16$QypK7I`+suP2J}YIjlmHJ%Da}V5~cI1qz8>0T9>?* zc!zrQA8Y-DT!vb#j>DVO?l>P%{3a-+l*8}lL{<~Ya&O)QWX1a;_|dN2mFs*L8=9?r+>Xg2)P`F2RBv z0=_2&Ry%$?DM|pHehDu@fG_XwzW1S(#48h%ZO{uww*@m_cL#c8k?InsdUBgk-^G9*hT_M zL|&Onpt|=IehhRViX&PS?Ln7<)Z)I>vt*)2^G36abP+Hd(?NNP!-mM1k#X_zDYmbN zmXUX`Gv)d+1*n4>q-ry(dcSt*y9u$N6r}tjh|>QgfH?n!INSK~_Wt>qR=BZDA@aYQ zQI6JqG??dBatxiW|APiAJ{zkdA05nZGG)$D&-ZJPf@T zEh^bpijZa=LKzRO8Q^29QS1^&>|gK)KLjm4uU8_7m zu8=!6dx;O>)xugmlqY93aZm3DLJ=0&Jzr{0qNt`W|EC;kbi`^Rt}KC+vY$Nj%>Ze? zJXJ49Sa-;4@QMiybg>3YIgiXhWpSsTKw8nfq=o^||H)3Y^O3wmaqbO@9n|*-#Kt*i zdHYvc%AttBL;2_0vuJ!nJ5&Ngi{aM;1{FwO4{<|mBsa|}hRUD_> za*#17(dho5bwL!;GXeVq%gOX-Mq(P=lqm)Wo&GSSlW7*1XB$N`8 zxui+8g|ww28dOLs4QNuTb3ZHlJ@0$2bG_Gho$q|#IqSOi`?^+Z{nvl^4bOAm_j5m- z)RmX`AWkhR2ZWuK697WY><4*oi5d*&Dzce;chIJ(IXU@i*9?H7 zygXX(J=NKcHSBEw=!g*KVZmV??5t?ORx3H)$3wx-WMV*RRG0y|585N5U^2#MiHldL zOAEQGpJng5hO3~3r|$Kr_d0g;=nI%UV!1)yKq?((%4=XbOsocszBo8cQ=uu-6$=cO zChmiwiYr&9lO^%Q_!x4!-z)87Y(&r%dTMKnEgsMd#N3m2U~c;HM6MypwdchFOcT+C zLVV!XC|%W~bP(NS<^}Er*bGc@a;Sv8bfS`1-VzKjrcwuhWFMa#>b<@UrsxO)q5c9& zAu}&fD*ZU&lEDB?QUSf<NMSx~$!HPd~W}Vt88H~A^6ic)iH-=Qr!;rUDLap)N zVfV9V`FU@b1M+j#t9|_V2m;K>izXElcIa8*ybyyw{0x$WI!+V$08Ru;6q;gzKTCAg zdknDT9|M1`K2N0$%#g4XFJf|QB9O+sBEMdgu22O&UunxLHR<9GPpJ0sRN$XbfF>#z z9%DVgc7jF>M__a?xj8Eb3_6$a>S0-7+y2nHV@2CPRMvvB#h#|&>VW0Z+T9U$HPp+S z9k7^f+&Hb3n*%Enu8*B%wHTApJz`s39Ko!ktE&bYDz?A^=>mdng;y#t6%u4rJSyY^Llzw+gWmO}57Z=oe`j_+=eC7)sZJAAyy>;h}-B zP!{b*KtypXz>}O|&oix^u-_QKBcy{g0VlYz%58?VqqVx-=9dfQczd zSPQ73j%}-kQ4~K7;0X$NIdtQTu>w*!#Tm~D5Dqh`nwAqv&@fql?!?K))(#FEipIKG zKhpq6IFCg|$ufnY>|H*9R0N#vOC-rZk$J3&+S)0ZLv^Us?JSxYEkXg0p$PkoZSpSr zVR|rs#kvOK%@i>>wkCig&``-FM_U8@`cX9nJD;J7i>eJjl+a+6WSI~<^YeEi(5^-u z#3hufgAAhl5Ls6EHwk{Uq({~C$;k{1{-YOw#vEFH5Yrs!(IJN6d6+g)zZgRA4jtme zm)R={Aq)k#k3K^&Hao&D-fHVvr4heCKCW*;8utLpH*T~qFP-&aQFu72!4X0sOvuUq=o8pvL{9q08+?L=4F4D zl{sKSaocbbFHF2MCvz4O#20wHgj@ihG>fnSxVsoownOxH1YIN0d0t0mBv0+6qy&-9 zqq_5ilwoMcMV&r%YOn%92URBn`vby)ecaKciJ#DnqVJU~5mDL!IeD=IhS3*bn?n>^#jVKxsgvGZzvS%zj6xEYZL@HDe!{8d(c7eDAcRuoRAObiK$7rH4yrxm3 zp^I`{s=o#81cWPIkfs7-ybia9wsR6k0r0^BWP(`)4vy>Hz{%+7{V0JT_RnlBi2hKW zMGGTk3UR?3%V05@#Fe!|dZ1*WWX(_joI2y#p%=Q})LdbgzE4Df_px578Zr&4=^>r z!wZJZ9LnHmoBY?LzNV}HE{8wxji z;*+}MpWd30leBy;k~TJ6e0VuGgd*F$(IWBZug4*mMtXi|Ij=qs`!mI9Hl9`H*p%2u zlna*zb$+>^;2&R@3sMg$hfuhIr?3z6=xLaHY3=CTc1t zufGIpH|lI)Sc2sOvl?0-I&H1{;Bw@or4LFOUIZ2c)6>6?S>AK;BdSjRzTc);Y9^1g z01^_IM&f?sX@ZCQW%8!a0A~0%b$0* z_=B~NsmCg`K>`iS%gO#=pgXN=0Oc@7Yu0fv`U+eZfQ}%uF+eFn(0ox-Q!HmtYoXI4 zgE4IRQ+y=21mm7;@-gF<;%brJ%fvF!!*&2H%ad+zv{Ype7IQ>_2*l92F9z_`YiHSF z^1r}lvT*X2w5-NtM}d4O2$D1CJB8g|kC%a-H?U|H$F;WD0?}uXKO~XN1VE9g65zLR z#ltiTLPMaCWAx&Nl4CF;S~6n6^SbfnnJ}zUswxzU0DNsimuB4I;v)Dd12fxZW|j)+ z17YWLjvu!Ek%l23$v=O=&!Ovu^@5lVKpsm0_&}o&{*H%eDufz8Z=9hfRt)q;&P0|E zq6P9Eu?xdhFcYyum!ipg%N;d79!yq(uvS0;)^@748a^M$YRvr|)Irg1VtIm*r}GFmvX?}OHU1;&@OPT=^bwe16{YKG^?xBM*tgyX22N8O?k9`0$G zlcGxcBF!T7Ny3d z^oPls@T^(y%?pi+$FiGRXOen8bwu5+a^)N6$WhKU!n`X23v~%x5q- zr5P=w$WqdAXoSD$zpzAEx%TQH+9Mhwgw43ffs5i>!o`qi0SJVxy&Ag{VWGIA*}UNl zhIL;bco2VqAkE$5aa|+k2Z>yUeTLNKuegBQ2D7+_^R#&QN2 zk)@Dvf`tmZw+sN3WXO-3(63y^ibi+pU^SRjJQ0dgz)?c)!&Nu~8j>npxB+r19B9t*Kii5PV11zo z5jUL9Tf`X>F97Z}&`Ltzc>(E5+({|~zlz4(JK@45tT8#79>BZ+kq@~LsRRzY{`u&U z`j{$)DEWX*6Q8`k`NT;P_!KgpuYXeP64tehEI7sO#`qV;*mgOji__O878o%e>6xg! z1gUI-$Xdz*&rNVxe%UDHirvJ;736>SM1HjC@@H&Hxs@@H_$39FB+>|J01^pQIMT zcyKNerurO=bei35Z78cU0cT>mYgfG$cPSpXnF)iDD^0UE8C{gf!ie&gA7f*%Q?k3c zQ^tUF2#CGqWF`kE>lJKnfbn(^ZiJ8%lsipZ5Ug9E$&0BR5HY+DKa*1Cb z>lvboWvy*`dU_*cIr^^@40LsMw+gnr{{(^^uYYsdmfN_9?;+%W2t1-j5PE7uGORDdhPwycmq9qRe26VQV>KoCa*yVN* zaBl2Epy#(EpoM4zR7LmQftkX>X~-Os1_1F&AOADxT!W{V*VuV^>}cp(S#V1pz968z zT+Yo!DDUC};PJTl#OIEVFZKJkdV2O(dMpHQ3cD7VU3eTnaHpXgc(94BZ7Ti1q{0D< zWrh81KZ~>6Q>Tu%v;uQWD*z>K24$Rn z^Q#b+4c0wdmw7R0w21S^E5t3Ur@Q;oI~}PqsqMZxp|YD3(}=)MTDcjUk;`ngkyJDr z#DYiJInY6DZyNWskk*rNG(JdS6c$j4yJNT+h|4L7#>en!2o~FKo@_LTk)?jUkW)zb zxj;8c)I35ZGAPGQE06fXD`-VyD$`*GB$K@>!s+3Ms z5p8|D+?@kegp(6ROc*Kzo?X9woues&&OBM|MQa(&Z3* z9gyH3pdtmF9~CbkfP_Y3%S|c4lDl}u#MDq4fRl9@_@newrS;R;#fge`$EXMt88!tM z&;$-1afP6U%mqlRpr!RTwF}82Kt3Zly+l*d9w{ZEaRU&6A95efiNrRFsQ(p-nK9%_ zCF>p>mtGS==1^3fKzJ9nEz*Mmmx3n14MmnvHA8d@4s5oBM9-JHxAb{LB((QolV!d7 z6AO7$a6@TH2_c*~6NhKLXU)(0!oX9fuan{vd)gAI z;@e5t*!)!`eG%0WSb+_db{9N>%dUdVR&!KvlLr9;5Fd<^N<(3U&O*PrJFcyd-tq>IQ*-hmTrjxh>zdQ2o zxI#Zj!@l#J+kg>)ElJ+8sfC4Flqg9s1FwjyY z5F^jDA`c(#c*rAJTQKzYDk52;>@+SHhxQq7*f6~Q*u#L~@88LGmI|h@47SJE35tkZ z#_%VF4vr^TTlgLF8xm(Gkab7K?RRt}0sZJe4$3GL?;HTb0+*Vj4YliZbV7gj zrKhR8D7u`c0NlA~MgnYb%-dHUzrvR4YogywK+%SHuIjR+j^XN7J6#7fc?N^`t=?rv zl*mfwco+^f^VP3&eOGoAv}()_pE|F!F98!{LtP2`&WXkz^gyyiqJvL`qdo8Sq!&v| z>!K@db(%rU)V86y@ISYLWftP8zVCU=Y1697tQ&<}y7yh8MONsc!}!E`++x=~=GrT* zz!ap+SP-@hb@>W~!xvGbBtLCUv!+@A$baNxi}`YeS#|@l(xr zcK+($_mGDSI8p+a4x7mu#-BG$)$c&A$2HhpRhwxxKpjEA2c&bl+_%TNvL4H;k$7gD zYPhxnE*IyzK){qWbJnbjsOjo}+CL&-7IHN0fRJ>ih809QfUV1f(i-}{eXGHICf7H2 zonRJ?wc*ytCMQdI9}>1>>zMJ_M;b{OR*xiQr&_sb<10B1z>Esih{&mC>Yzhv0K5yA zEn;;AHsn;&PkwJt8G0jsQF{^gKbYpu68Mehajx5Y`pBrW&v=SQD$i@!2g>mYGQY$f z3JV)(^mzUyJVz47U7x;`a6C%)Q>kcIsjh*i{U)j&i!_$RxZ4cPPQy+vRD!0xk zF8pEX{D)yMa7$dYZmN8`vDWuA=n>DVU!ezbE_lRI>^J^IHMfhjL!m46qy>3qLM`4}d(UIiGQbvBJ35P9q z&+Ck6t*2wd1`5bcp(ka@Gk#5()D&F{Of8y)KP zd7`y_#}2a>+<&{FkD^} z4lPI3m{GLmVEo&_ZRX+ zNr;qjZGU5~8+qywdEd_qq0-2feRu*pw#c z{e{RAY|ItliwGMb_7&|P>;Lx6%)#L@i9q+1F=-phlsubp=~4$+W8h25`BA4%36`!2 zYBmC!1u4!YsQ50!uN&GyBfs76Puw7Z8f0{vtutWHlQn>ZMM-5HfmvP%_vvk?@CkXXG@WU(W1ooulkxZYk>j`3DBz+x$dUJw6C2i)@z%wo8Z{&9IVvQ;reZyN;Fs0Y z)g|6PhE)yL2|I8A{iu1F2o=@tmY0!>CWds5!@^LVBODY80L7?Y+(oP?Y6pn!&Infe z@Kk&Z%Qs2qOngM*m3Kf=+>o6mh{6>@i)+L5?{`4#GE1*Kuiwx zwnv2!oT3Wkwd+D{4UI-eI%b3zO>0)bCcp*$6VP<d`#j%hYo1BEih ztiz-{tLUEvtp>%Lh@<&`jV~$dm%xUlV$`v~6%ZKtjw4ieOUn4HT@F|Qt3BxY?U*#O z#^;>XkDS1U4$1hyi4;HfPWVyo|0I5) zw+n?(uyDNyt0)ujBVXemZX=;1D)VsoC(X@P*i)6f%tyX|UyL0Fk9yHmH#{JYM5fS~D*SF-LGrpQ#cm;t{;x0sMM_L!1 z!G5GXHWmK(me~b^iNGo~?#Uz1>&MJpymV=WXFQO36=hYl?KuV2m33#%=*UQaYougn zbjXj?^@pQ(iyPoN$nmn{;07!rUTCHxw#yqbsr2?-Jf#}?c>>lX0$h}pl|K7rnF!&hT9} z@&b{WkW8q?Yt>Fj?h3zu6d&vHDN<^hZa3W5iiq%C3+KVA9frulYE?b4@`MbRN>aG( zyUq_MK*c6lP10FCT=yG?!fN5Ha~&~az`7vZ@AZ;_eFrnW!Ve!7^{;?TXYZ2ahHh^n zlqu;tmY3_^cFZh&yXZ9!vS1#`2^m#|%Gf{90?--7{&3h;2^v%VD%|XBK`{48)wfls zSc9Jaygl@n6wOi(3@9IS zae8nYiG`I_?=~+tbeyj#7x7>S7`c9L2@~)f|KXRtBnEspdHttPeJCw>Nayik*ioiv zQ@|jMRkZqVR81{wvflY7M5z)uI|VdvwZvF7UCqN=kcx0kS~y6 zGyj%6!ha{H9EXbbrqr4b+=2!a)@k&zTHfeY z`?z$Ll`6ceOPl8m_4oUBujv*?0=m@9V!hucJo9L7y;Q{CKodT`Y_o+lSmn;Vpj-AI z4H~f~eYz=GGPDCE1a6y>)PRlsUpc53sQLE5ujIbX$0xTJwsp0)@AJL$TT-RH(`wB> zu~hLHe-i>hQ^i^`P%H#h(M(&C0oQ{BPbo1z80 z_0B6(R;kj;x@(t{!<)XozTij=rS^!N8J+L11bKb%RrPNM%JVgkBikhd1utKwXA!P)evfcDet+Q>h;j;=|K6p1jWI1`W45$PuSXh-p?V%t(UUL^ZeAL%8zDk zd+kF;8(x+;SZw&3>7roYS^B%;%3YFfZf<#)r1x{xzBDecv3LTfVEybVTyAII6-vj& zt*DzBwSLEEg>o4_$<+Y(@%m3f_AU+|VR@*#`cY)V3jOH!Hl-16U-}ks2p`<%;OMyGjyaNL_Onyj^(eOh;qICW>>{iB zb3o&H4y$6%q6!aFgE8m?Hc1!n7o9=&yDoJ`M~)nE^}RnlJj~Icwa_Ng+i(JV#hPxB z)N(hZ8`v=Y-r}|T3?pi zA}R-!hiW&L`c=!G{BK5PL;ips&jT(^6r1wx_w^EAI)BeYNUH)Qp|oP|?AdOoR=q$9 zz^C2j?BwKr*~ZMm;y@>FJNZf@jaV|HZv}EBWsQremG(6d8aFwG5Lo0Zb`EPOp<421 z^PU*`A;;^4$8KL|<|PTg4>Q+#z)2atpnDZai3D5Sg`w;mt&ZPgUqaOzah z_w<(NYVT`E9&DWEbL+L=hrgsU?I;wksMQA5p*v+-T3KK33`s3>0nL8F**wFipf_$p zab-lDHZrh=&D+Qw2X=d<6}z*x6L&1%P>6adGu8?;J=%WVyyHyyd&uKA2bENz*d3*} zYbpi@1`?dCfXiCu4{`}u zv2=$@w%b2H2}J3OCYmeY$xxSr>e}#j`|MTM_YAh$qa zX>2Lu!HPWV*7yw8_y9!B&GD;D_&V1ul?n&eaay7p%$PuA>T*-lRMw;-nAmh34~IKZWMaI2L=F5PYLP(GvdGX#GXNZQ>c;a|LD3I~=03xcyX!T%9RI;XoK78Nao&mhd0rQ<&>?N=CtxXy4UzGE<7dl?jQ>RN-p-Yev>5Hk>2x(BFqTTHtn}ig!D%8~T;aA^I(R&@Bp0@&vOSu6F!+nl`=YXb-xKsjd6H9>txq!0umnN}5bFJC4E z$MA7psB3^QpO6oP=owi`($WvxJOuBPpEcj7-c<{)`KDq&34(Gsz3w)$7Wm7(c5IJG zNlC#KXGSv4Ng=HxRj^J!LrB)p_50o`S{xEtm1i?yR|FK~+mQoJH*F*B|4Qzt?IVH| zEErVlO+SF!AEO$m)%n+{l?YKeHTRywPz1S_n09c!@%$Jl>e8pi+V|N^j+w|%zl-B;IRthp#gldg`22|^H>`-Vqp5QA= zBl-t|fqyG2Gt~Zs&g(7&(>cSkl`|2!`XhC39L!3`uC=;1|NXs%_wueHM5N}UPA)Fq zZ&-m?vv8R78@%Ct+z90)3? zqbQi9dbukF1x?FxvY}Lj3!ZG)t^xS0)xj|~8w6zBxDkfPJ?A$iat+*izQ@Gpn(fe9 z%xUh{m^Z@Pelp@z#>x*2zUyz_T7rBEkkHOu2aFIOe;1p{Yu<`1l6?((JUx7Jpp4IW zHutq8@C$0AVpiD8b5M}Wb43uUzUE1ch>Bc$^kjc_!N;$QlB<2zxU*2z2Ez?ujnLrz zsCGvypVenI{Hm7@W#Bv1yN-b4qqZTfUs+d3^ z<+cr?XpQaS9x|@M(>m1XtF~e%R{>mY96?|O#u-b6XM6(C2q>{1rY)u-uB%B58ZzD< zawRp@wm9Sg-F4jBh2J=b4Tz2$O9xH5xoBdnx5-=PV|u!50lX!#RdMsAHnz8}1xz|V z);wW>MjA8Dyt@=1|F!}#DtX`_V8)Kqci&)FYcQx(EVwG4RF$F4GS(j3iiFujUq6CE ztv1G~{-)ihuuMZn<~vr11T6^cA4z1%Z6oKwoWcJ7PY5-(0nDMM9a!dv8^646Y`g|- zKnEyiqqDwmKf8THnJcN#Ks?rfcgZCRxQAc@sK+db0R+|<^!3oOhXjaWbGmQAMNYtk zT#<<(x!=FOVY78kODghIs*M0r`q(9B)O@uxZaWsh7l|tSNlBGcUx>m?oGew6vTcJF zE-WZCBIpVDDvDU2AK-ZdE0C>ts#r2I!L&F5T{7Rm40rXxT_Kq#jN>n%Q>P;+I>hK{ z)-AJ0tpy(;sLCPCYs@={f~suP#^K=`laVti8$ucKM?-UNPbwrKN#mE)`g}T*rEwT@ z0LE<8$`PzSm2?2qMm4;P*$%|@ggd&pG(%9;WIvj`jR%_oH2<|AEj8_@ML~^^o#{oP zj9^KOOE7>Sa4M$2>wXFkfW1HiaE$ZNViXHe|3?xmSX%a&ocyu zY;{y_Sqh~e2^w&NFaz983hli2p<0%_JW242pp>*3u(Bc^1UnT^&?vUU0r-Y@0ZiKt zWQJ;5AcV+yqqT6<3`O-g5{Te{&w(L#6bd4nfeUmChY4uU1Tc@Z3YBL#{Y#LxOyS`% zTdr;M`SnfG0$;EbK)DVabNxOS`gnOE0wE6~tVAT+04Q2;>l`HhtaEc!$2+pxAHja; zY_-%)xGmze@Lk+kvlugUXKB2|S_R&c{1(J_4MGblp;>KfZ2Y{ktLEecpZCxML`q9! zWgoS+ft>LC@c4J#roon$mZa`5@wyW6g2kxR#$#E2xnZubaR1zfb|cmmxSIsKYOGXM z9WCSHRqC!lj0`gAMT?9eXU~3=AX4$w1v@maDR7bVVD#(*Q8QA>3bu84gEb?hDk7JM z!Kaaamh$0$CsF!0>ZSjVKZPnxKhI>8-??{>h`NYBx;r~BGB|RnR<*TjYe2y2DR3?* zVM0P-wK78yX8XSOTYfhh3WPc)i--B};MbpEvY&UOw zdI9=le5k9<{CTKqv*5<+l~38Sw*0r1pNGbD9{aFWj4flg#uo^F{P^+QAD%~UO&-SU zlmFnTjZ}Wm?58|*jQm#uip>I?=os#DFD)w;E=>%E@7b(6rRHd!lCI#TnQ^x`>Amb1 z0h(PMi@4~6328%e3iM{5Sg*x%f9?6q?9ufG-LWXL!I$#~yF`u0rqP*towm$qq&JJ- z7X)j*A5ajq95O!5Z{khwwcO-4f9|dQ^tlT~2w;@>VmuA2cRppGg2u+XX%FCIpwQeS z5ZpQA!gYn*?OVj{cKM!i!-w$OBNVJZ@gue&OYMc=hG4e=i2rz5wsLI zyxS|u)REq1xU@-T@5@cGbF;oQA=44`bPm1Q_-b_IsP0}qo)Y*OKS(S8WlZ};5DISa zm!o6;+XH_1dw0d9%(LtFMxqnrrs)@9+CzU`e!0HCNi}Tue2Xe@w-VFLWDW?KZK1yu zTW7xVNj*A8^tac0`gdecv{>x<>Q8?V;p6FV(g<6pzr%XPx30SOJ3FuUYVC5)fTkVa zYOBxQccV>P^?A$l6^(ZN+p!xRt@AN6bB-0(nNJTb)NEj*zj5>CrKasCW~(m~3|0^^ z`n`X`;OY57_5l{(+cZ_;cnEKFPtshGpWTPF5{ewMi^3%hc zr$@xdWX0UsULBb5!-ajT^W!&fi7HHbA-z;pb?DC0kY{ZN`~GlM)2r_6;&4ky6YPW# znh_e^6?~! z8y81=I}gu)J^=kHUCW1W;WcGgL+C$v!2Nu&uLXz1sj$4{XP9!NX|51Gu*U_m1&D0Of)GjQ{`u literal 0 HcmV?d00001 diff --git a/androidgcs/default.properties b/androidgcs/default.properties new file mode 100644 index 000000000..e2e8061f2 --- /dev/null +++ b/androidgcs/default.properties @@ -0,0 +1,11 @@ +# This file is automatically generated by Android Tools. +# Do not modify this file -- YOUR CHANGES WILL BE ERASED! +# +# This file must be checked in Version Control Systems. +# +# To customize properties used by the Ant build system use, +# "build.properties", and override values to adapt the script to your +# project structure. + +# Project target. +target=android-8 diff --git a/androidgcs/gen/org/openpilot/androidgcs/R.java b/androidgcs/gen/org/openpilot/androidgcs/R.java new file mode 100644 index 000000000..31e90ffd1 --- /dev/null +++ b/androidgcs/gen/org/openpilot/androidgcs/R.java @@ -0,0 +1,31 @@ +/* AUTO-GENERATED FILE. DO NOT MODIFY. + * + * This class was automatically generated by the + * aapt tool from the resource data it found. It + * should not be modified by hand. + */ + +package org.openpilot.androidgcs; + +public final class R { + public static final class attr { + } + public static final class color { + public static final int all_black=0x7f050001; + public static final int all_white=0x7f050000; + } + public static final class drawable { + public static final int icon=0x7f020000; + } + public static final class id { + public static final int objects=0x7f060000; + } + public static final class layout { + public static final int main=0x7f030000; + public static final int objectbrowser=0x7f030001; + } + public static final class string { + public static final int app_name=0x7f040001; + public static final int hello=0x7f040000; + } +} diff --git a/androidgcs/proguard.cfg b/androidgcs/proguard.cfg new file mode 100644 index 000000000..12dd0392c --- /dev/null +++ b/androidgcs/proguard.cfg @@ -0,0 +1,36 @@ +-optimizationpasses 5 +-dontusemixedcaseclassnames +-dontskipnonpubliclibraryclasses +-dontpreverify +-verbose +-optimizations !code/simplification/arithmetic,!field/*,!class/merging/* + +-keep public class * extends android.app.Activity +-keep public class * extends android.app.Application +-keep public class * extends android.app.Service +-keep public class * extends android.content.BroadcastReceiver +-keep public class * extends android.content.ContentProvider +-keep public class * extends android.app.backup.BackupAgentHelper +-keep public class * extends android.preference.Preference +-keep public class com.android.vending.licensing.ILicensingService + +-keepclasseswithmembernames class * { + native ; +} + +-keepclasseswithmembernames class * { + public (android.content.Context, android.util.AttributeSet); +} + +-keepclasseswithmembernames class * { + public (android.content.Context, android.util.AttributeSet, int); +} + +-keepclassmembers enum * { + public static **[] values(); + public static ** valueOf(java.lang.String); +} + +-keep class * implements android.os.Parcelable { + public static final android.os.Parcelable$Creator *; +} diff --git a/androidgcs/res/drawable-hdpi/icon.png b/androidgcs/res/drawable-hdpi/icon.png new file mode 100644 index 0000000000000000000000000000000000000000..eab1fc68fd7ad531ac025a53956f78de8d4e5180 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926
r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 0 HcmV?d00001 diff --git a/androidgcs/res/drawable-ldpi/icon.png b/androidgcs/res/drawable-ldpi/icon.png new file mode 100644 index 0000000000000000000000000000000000000000..eab1fc68fd7ad531ac025a53956f78de8d4e5180 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 0 HcmV?d00001 diff --git a/androidgcs/res/drawable-mdpi/icon.png b/androidgcs/res/drawable-mdpi/icon.png new file mode 100644 index 0000000000000000000000000000000000000000..eab1fc68fd7ad531ac025a53956f78de8d4e5180 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 0 HcmV?d00001 diff --git a/androidgcs/res/layout/main.xml b/androidgcs/res/layout/main.xml new file mode 100644 index 000000000..3a5f117d3 --- /dev/null +++ b/androidgcs/res/layout/main.xml @@ -0,0 +1,12 @@ + + + + diff --git a/androidgcs/res/layout/objectbrowser.xml b/androidgcs/res/layout/objectbrowser.xml new file mode 100644 index 000000000..02a3f5dd6 --- /dev/null +++ b/androidgcs/res/layout/objectbrowser.xml @@ -0,0 +1,8 @@ + + + + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml new file mode 100644 index 000000000..eba6becf8 --- /dev/null +++ b/androidgcs/res/values/strings.xml @@ -0,0 +1,7 @@ + + + OpenPilot Android GCS + OpieMobi + #FFFFFF + #000000 + diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java b/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java new file mode 100644 index 000000000..190668d80 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java @@ -0,0 +1,99 @@ +/** + * + */ +package org.openpilot.androidgcs; + +import android.widget.AbsListView; +import android.widget.TextView; +import android.content.Context; +import android.view.Gravity; +import android.view.View; +import android.view.ViewGroup; +import android.widget.BaseExpandableListAdapter; + +/** + * @author jcotton81 + * + */ +public class ObjBrowserExpandableListAdapter extends BaseExpandableListAdapter { + + // Sample data set. children[i] contains the children (String[]) for + // groups[i]. + private String[] groups = { "Parent1", "Parent2", "Parent3" }; + private String[][] children = { { "Child1" },{ "Child2" }, { "Child3" },{ "Child4" }, { "Child5" } }; + + private Context context; + + public ObjBrowserExpandableListAdapter(Context context) { + this.context = context; + } + + public Object getChild(int groupPosition, int childPosition) { + return children[groupPosition][childPosition]; + } + + public long getChildId(int groupPosition, int childPosition) { + return childPosition; + } + + public int getChildrenCount(int groupPosition) { + int i = 0; + try { + i = children[groupPosition].length; + + } catch (Exception e) { + } + + return i; + } + + public TextView getGenericView() { + // Layout parameters for the ExpandableListView + AbsListView.LayoutParams lp = new AbsListView.LayoutParams( + ViewGroup.LayoutParams.FILL_PARENT, 64); + + TextView textView = new TextView(context); + textView.setLayoutParams(lp); + // Center the text vertically + textView.setGravity(Gravity.CENTER_VERTICAL | Gravity.LEFT); + // Set the text starting position + textView.setPadding(36, 0, 0, 0); + return textView; + } + + public View getChildView(int groupPosition, int childPosition, + boolean isLastChild, View convertView, ViewGroup parent) { + TextView textView = getGenericView(); + textView.setText(getChild(groupPosition, childPosition).toString()); + return textView; + } + + public Object getGroup(int groupPosition) { + return groups[groupPosition]; + } + + public int getGroupCount() { + return groups.length; + } + + public long getGroupId(int groupPosition) { + return groupPosition; + } + + public View getGroupView(int groupPosition, boolean isExpanded, + View convertView, ViewGroup parent) { + TextView textView = getGenericView(); + textView.setText(getGroup(groupPosition).toString()); + return textView; + } + + public boolean isChildSelectable(int groupPosition, int childPosition) { + return true; + } + + public boolean hasStableIds() { + return true; + } + + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java new file mode 100644 index 000000000..19e9b2812 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -0,0 +1,21 @@ +package org.openpilot.androidgcs; + +import android.app.Activity; +import android.os.Bundle; + +import android.widget.*; + +public class ObjectBrowser extends Activity { + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + + setContentView(R.layout.objectbrowser); + ExpandableListAdapter mAdapter; + ExpandableListView epView = (ExpandableListView) findViewById(R.id.objects); + mAdapter = new ObjBrowserExpandableListAdapter(this); + epView.setAdapter(mAdapter); + + } +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java new file mode 100644 index 000000000..12a4263c0 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -0,0 +1,27 @@ +package org.openpilot.uavtalk; + +public abstract class UAVDataObject extends UAVObject { + + public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) { + super(objID, isSingleInst, name); + } + + public void initialize(int instID, UAVMetaObject mobj) { + + } + + public void initialize(UAVMetaObject mobj) { + + } + + Boolean isSettings() { + return null; + } + + UAVMetaObject getMetaObject() { + return null; + } + + public abstract UAVDataObject clone(int instID); + +} diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java new file mode 100644 index 000000000..a1e5773b9 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -0,0 +1,50 @@ +package org.openpilot.uavtalk; + +public class UAVMetaObject extends UAVObject { + + public UAVMetaObject(int objID, Boolean isSingleInst, String name) { + super(objID, isSingleInst, name); + // TODO Auto-generated constructor stub + } + + public UAVMetaObject(int objID, String mname, UAVDataObject obj) { + // TODO Auto-generated constructor stub + } + + @Override + public void deserialize(byte[] arr, int offset) { + // TODO Auto-generated method stub + + } + + @Override + public UAVMetaObject getDefaultMetadata() { + // TODO Auto-generated method stub + return null; + } + + @Override + public String getDescription() { + // TODO Auto-generated method stub + return null; + } + + @Override + public int getObjID() { + // TODO Auto-generated method stub + return 0; + } + + @Override + public String getObjName() { + // TODO Auto-generated method stub + return null; + } + + @Override + public byte[] serialize() { + // TODO Auto-generated method stub + return null; + } + +} diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java new file mode 100644 index 000000000..c5ffc9d21 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -0,0 +1,117 @@ +package org.openpilot.uavtalk; + +public abstract class UAVObject { + + + /** + * Object update mode + */ + public enum UpdateMode { + UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ + UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ + UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ + UPDATEMODE_NEVER /** Object is never updated */ + } ; + + /** + * Access mode + */ + public enum AccessMode{ + ACCESS_READWRITE, + ACCESS_READONLY + } ; + + + private Boolean isSingleInst; + private int instID; + private UAVMetaObject meta; + + public UAVObject(int objID, Boolean isSingleInst, String name) { + assert(objID == getObjID()); // ID is in implementation code, make sure it matches object + assert(name.equals(getName())); + this.isSingleInst = isSingleInst; + meta = getDefaultMetadata(); + }; + + public void initialize(int instID) { + this.instID = instID; + } + + public int getInstID() { return instID; } + public Boolean isSingleInstance() { return isSingleInst; } + public String getName() { return getObjName(); } // matching QT API to the current autogen code + + public abstract int getObjID(); + public abstract String getDescription(); + public abstract String getObjName(); + + int getNumBytes() { + return serialize().length; + } + + // The name of the serializer and deserialize from the autogenerated code + public abstract byte[] serialize(); + public abstract void deserialize(byte[] arr,int offset); + + byte [] pack() { + return serialize(); + } + + Boolean unpack(byte [] data) { + deserialize(data, 0); + return true; + } + + public void setMetadata(UAVMetaObject obj) { meta = obj; } + public UAVMetaObject getMetadata() { return meta; } + public abstract UAVMetaObject getDefaultMetadata(); + + /* + // Unported code from QT + bool save(); + bool save(QFile& file); + bool load(); + bool load(QFile& file); + virtual void setMetadata(const Metadata& mdata) = 0; + virtual Metadata getMetadata() = 0; + virtual Metadata getDefaultMetadata() = 0; + void requestUpdate(); + void updated(); + void lock(); + void lock(int timeoutMs); + void unlock(); + QMutex* getMutex(); + qint32 getNumFields(); + QList getFields(); + UAVObjectField* getField(const QString& name); + QString toString(); + QString toStringBrief(); + QString toStringData(); + void emitTransactionCompleted(bool success); + + signals: + void objectUpdated(UAVObject* obj); + void objectUpdatedAuto(UAVObject* obj); + void objectUpdatedManual(UAVObject* obj); + void objectUnpacked(UAVObject* obj); + void updateRequested(UAVObject* obj); + void transactionCompleted(UAVObject* obj, bool success); + + private slots: + void fieldUpdated(UAVObjectField* field); + + protected: + quint32 objID; + quint32 instID; + bool isSingleInst; + QString name; + QString description; + quint32 numBytes; + QMutex* mutex; + quint8* data; + QList fields; + + void initializeFields(QList& fields, quint8* data, quint32 numBytes); + void setDescription(const QString& description); + */ +} diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java new file mode 100644 index 000000000..3091595f0 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -0,0 +1,332 @@ +package org.openpilot.uavtalk; + +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +public class UAVObjectManager { + + private final int MAX_INSTANCES = 10; + + // Use array list to store objects since rarely added or deleted + private List> objects = new ArrayList>(); + + public UAVObjectManager() + { + //mutex = new QMutex(QMutex::Recursive); + } + + /** + * Register an object with the manager. This function must be called for all newly created instances. + * A new instance can be created directly by instantiating a new object or by calling clone() of + * an existing object. The object will be registered and will be properly initialized so that it can accept + * updates. + */ + Boolean registerObject(UAVDataObject obj) + { + // QMutexLocker locker(mutex); + + ListIterator> objIt = objects.listIterator(0); + + // Check if this object type is already in the list + while(objIt.hasNext()) { + List instList = objIt.next(); + + // Check if the object ID is in the list + if( (instList.size() > 0) && (instList.get(0).getObjID() == obj.getObjID() )) { + // Check if this is a single instance object, if yes we can not add a new instance + if(obj.isSingleInstance()) { + return false; + } + // The object type has alredy been added, so now we need to initialize the new instance with the appropriate id + // There is a single metaobject for all object instances of this type, so no need to create a new one + // Get object type metaobject from existing instance + UAVDataObject refObj = (UAVDataObject) instList.get(0); + if (refObj == null) + { + return false; + } + UAVMetaObject mobj = refObj.getMetaObject(); + + // Make sure we aren't requesting to create too many instances + if(obj.getInstID() >= MAX_INSTANCES || instList.size() >= MAX_INSTANCES || obj.getInstID() < 0) { + return false; + } + + // If InstID is zero then we find the next open instId and create it + if (obj.getInstID() == 0) + { + // Assign the next available ID and initialize the object instance the nadd + obj.initialize(instList.size(), mobj); + instList.add(obj); + return true; + } + + // Check if that inst ID already exists + ListIterator instIter = instList.listIterator(); + while(instIter.hasNext()) { + UAVObject testObj = instIter.next(); + if(testObj.getInstID() == obj.getInstID()) { + return false; + } + } + + // If the instance ID is specified and not at the default value (0) then we need to make sure + // that there are no gaps in the instance list. If gaps are found then then additional instances + // will be created. + for(int instID = instList.size(); instID < obj.getInstID(); instID++) { + UAVDataObject newObj = obj.clone(instID); + newObj.initialize(mobj); + instList.add(newObj); + // emit new instance signal + } + obj.initialize(mobj); + //emit new instance signal + instList.add(obj); + + instIter = instList.listIterator(); + while(instIter.hasNext()) { + UAVObject testObj = instIter.next(); + if(testObj.getInstID() == obj.getInstID()) { + return false; + } + } + + + // Check if there are any gaps between the requested instance ID and the ones in the list, + // if any then create the missing instances. + for (int instId = instList.size(); instId < obj.getInstID(); ++instId) + { + UAVDataObject cobj = obj.clone(instId); + cobj.initialize(mobj); + instList.add(cobj); + // emit newInstance(cobj); + } + // Finally, initialize the actual object instance + obj.initialize(mobj); + // Add the actual object instance in the list + instList.add(obj); + //emit newInstance(obj); + return true; + } + + } + + // If this point is reached then this is the first time this object type (ID) is added in the list + // create a new list of the instances, add in the object collection and create the object's metaobject + // Create metaobject + String mname = obj.getName(); + mname += "Meta"; + UAVMetaObject mobj = new UAVMetaObject(obj.getObjID()+1, mname, obj); + // Initialize object + obj.initialize(0, mobj); + // Add to list + addObject(obj); + addObject(mobj); + return true; + } + + void addObject(UAVObject obj) + { + // Add to list + List ls = new ArrayList(); + ls.add(obj); + objects.add(ls); + //emit newObject(obj); + } + + /** + * Get all objects. A two dimentional QList is returned. Objects are grouped by + * instances of the same object type. + */ + List> getObjects() + { + //QMutexLocker locker(mutex); + return objects; + } + + /** + * Same as getObjects() but will only return DataObjects. + */ + List< List > getDataObjects() + { + return new ArrayList>(); + + /* QMutexLocker locker(mutex); + QList< QList > dObjects; + + // Go through objects and copy to new list when types match + for (int objidx = 0; objidx < objects.length(); ++objidx) + { + if (objects[objidx].length() > 0) + { + // Check type + UAVDataObject* obj = dynamic_cast(objects[objidx][0]); + if (obj != NULL) + { + // Create instance list + QList list; + // Go through instances and cast them to UAVDataObject, then add to list + for (int instidx = 0; instidx < objects[objidx].length(); ++instidx) + { + obj = dynamic_cast(objects[objidx][instidx]); + if (obj != NULL) + { + list.append(obj); + } + } + // Append to object list + dObjects.append(list); + } + } + }*/ + // Done + } + + /** + * Same as getObjects() but will only return MetaObjects. + */ + List > getMetaObjects() + { + return new ArrayList< List >(); + /* + QMutexLocker locker(mutex); + QList< QList > mObjects; + + // Go through objects and copy to new list when types match + for (int objidx = 0; objidx < objects.length(); ++objidx) + { + if (objects[objidx].length() > 0) + { + // Check type + UAVMetaObject* obj = dynamic_cast(objects[objidx][0]); + if (obj != NULL) + { + // Create instance list + QList list; + // Go through instances and cast them to UAVMetaObject, then add to list + for (int instidx = 0; instidx < objects[objidx].length(); ++instidx) + { + obj = dynamic_cast(objects[objidx][instidx]); + if (obj != NULL) + { + list.append(obj); + } + } + // Append to object list + mObjects.append(list); + } + } + } + // Done + return mObjects; + */ + } + + /** + * Get a specific object given its name and instance ID + * @returns The object is found or NULL if not + */ + UAVObject getObject(String name, int instId) + { + return getObject(name, 0, instId); + } + + /** + * Get a specific object given its object and instance ID + * @returns The object is found or NULL if not + */ + UAVObject getObject(int objId, int instId) + { + return getObject(null, objId, instId); + } + + /** + * Helper function for the public getObject() functions. + */ + UAVObject getObject(String name, int objId, int instId) + { + //QMutexLocker locker(mutex); + // Check if this object type is already in the list + ListIterator> objIter = objects.listIterator(); + while(objIter.hasNext()) { + List instList = objIter.next(); + if (instList.size() > 0) { + if ( (name != null && instList.get(0).getName().compareTo(name) == 0) || (name == null && instList.get(0).getObjID() == objId) ) { + // Look for the requested instance ID + ListIterator iter = instList.listIterator(); + while(iter.hasNext()) { + UAVObject obj = iter.next(); + if(obj.getInstID() == instId) { + return obj; + } + } + } + } + } + + return null; + } + + /** + * Get all the instances of the object specified by name + */ + List getObjectInstances(String name) + { + return getObjectInstances(name, 0); + } + + /** + * Get all the instances of the object specified by its ID + */ + List getObjectInstances(int objId) + { + return getObjectInstances(null, objId); + } + + /** + * Helper function for the public getObjectInstances() + */ + List getObjectInstances(String name, int objId) + { + //QMutexLocker locker(mutex); + // Check if this object type is already in the list + ListIterator> objIter = objects.listIterator(); + while(objIter.hasNext()) { + List instList = objIter.next(); + if (instList.size() > 0) { + if ( (name != null && instList.get(0).getName().compareTo(name) == 0) || (name == null && instList.get(0).getObjID() == objId) ) { + return instList; + } + } + } + + return null; + } + + /** + * Get the number of instances for an object given its name + */ + int getNumInstances(String name) + { + return getNumInstances(name, 0); + } + + /** + * Get the number of instances for an object given its ID + */ + int getNumInstances(int objId) + { + return getNumInstances(null, objId); + } + + /** + * Helper function for public getNumInstances + */ + int getNumInstances(String name, int objId) + { + return getObjectInstances(name,objId).size(); + } + + +} From eed5705a6cfcdb4807170c4da95dbacf6d755d87 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 1 Mar 2011 01:23:10 -0600 Subject: [PATCH 194/543] Trying to get eclipse project right --- .gitignore | 8 +- androidgcs/.classpath | 7 ++ androidgcs/.project | 33 ++++++ .../.settings/org.eclipse.jdt.core.prefs | 5 + androidgcs/AndroidManifest.xml | 10 +- androidgcs/bin/OpieMobi.apk | Bin 148198 -> 0 bytes androidgcs/bin/classes.dex | Bin 12640 -> 0 bytes .../ObjBrowserExpandableListAdapter.class | Bin 3092 -> 0 bytes .../openpilot/androidgcs/ObjectBrowser.class | Bin 951 -> 0 bytes .../bin/org/openpilot/androidgcs/R$attr.class | Bin 358 -> 0 bytes .../org/openpilot/androidgcs/R$color.class | Bin 447 -> 0 bytes .../org/openpilot/androidgcs/R$drawable.class | Bin 418 -> 0 bytes .../bin/org/openpilot/androidgcs/R$id.class | Bin 403 -> 0 bytes .../org/openpilot/androidgcs/R$layout.class | Bin 449 -> 0 bytes .../org/openpilot/androidgcs/R$string.class | Bin 445 -> 0 bytes .../bin/org/openpilot/androidgcs/R.class | Bin 627 -> 0 bytes .../org/openpilot/uavtalk/UAVDataObject.class | Bin 1127 -> 0 bytes .../org/openpilot/uavtalk/UAVMetaObject.class | Bin 1440 -> 0 bytes .../uavtalk/UAVObject$AccessMode.class | Bin 1199 -> 0 bytes .../uavtalk/UAVObject$UpdateMode.class | Bin 1333 -> 0 bytes .../bin/org/openpilot/uavtalk/UAVObject.class | Bin 2255 -> 0 bytes .../openpilot/uavtalk/UAVObjectManager.class | Bin 5422 -> 0 bytes androidgcs/bin/resources.ap_ | Bin 140460 -> 0 bytes androidgcs/default.properties | 2 +- .../gen/org/openpilot/androidgcs/R.java | 31 ------ androidgcs/res/drawable-hdpi/icon.png | Bin 48558 -> 4147 bytes androidgcs/res/drawable-ldpi/icon.png | Bin 48558 -> 1723 bytes androidgcs/res/drawable-mdpi/icon.png | Bin 48558 -> 2574 bytes androidgcs/res/layout/objectbrowser.xml | 8 -- androidgcs/res/values/strings.xml | 6 +- .../ObjBrowserExpandableListAdapter.java | 99 ------------------ .../openpilot/androidgcs/ObjectBrowser.java | 21 ---- .../org/openpilot/uavtalk/UAVMetaObject.java | 12 +-- 33 files changed, 62 insertions(+), 180 deletions(-) create mode 100644 androidgcs/.classpath create mode 100644 androidgcs/.project create mode 100644 androidgcs/.settings/org.eclipse.jdt.core.prefs delete mode 100644 androidgcs/bin/OpieMobi.apk delete mode 100644 androidgcs/bin/classes.dex delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/ObjectBrowser.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$attr.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$color.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$drawable.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$id.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$layout.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R$string.class delete mode 100644 androidgcs/bin/org/openpilot/androidgcs/R.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject$AccessMode.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObject.class delete mode 100644 androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class delete mode 100644 androidgcs/bin/resources.ap_ delete mode 100644 androidgcs/gen/org/openpilot/androidgcs/R.java delete mode 100644 androidgcs/res/layout/objectbrowser.xml delete mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java delete mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java diff --git a/.gitignore b/.gitignore index a5af05849..c9478a9c1 100644 --- a/.gitignore +++ b/.gitignore @@ -64,10 +64,16 @@ ground/uavobjgenerator/uavobjgenerator.pro.user ground/uavobjects/uavobjects.pro.user ground/ground.pro.user -# Ignore GNU global tags files GPATH GRTAGS GSYMS GTAGS + +plane +quad + +# Ignore auto generated java files +androidgcs/bin/ +androidgcs/gen/ /.cproject /.project diff --git a/androidgcs/.classpath b/androidgcs/.classpath new file mode 100644 index 000000000..609aa00eb --- /dev/null +++ b/androidgcs/.classpath @@ -0,0 +1,7 @@ + + + + + + + diff --git a/androidgcs/.project b/androidgcs/.project new file mode 100644 index 000000000..c607dd2bd --- /dev/null +++ b/androidgcs/.project @@ -0,0 +1,33 @@ + + + androidgcs + + + + + + com.android.ide.eclipse.adt.ResourceManagerBuilder + + + + + com.android.ide.eclipse.adt.PreCompilerBuilder + + + + + org.eclipse.jdt.core.javabuilder + + + + + com.android.ide.eclipse.adt.ApkBuilder + + + + + + com.android.ide.eclipse.adt.AndroidNature + org.eclipse.jdt.core.javanature + + diff --git a/androidgcs/.settings/org.eclipse.jdt.core.prefs b/androidgcs/.settings/org.eclipse.jdt.core.prefs new file mode 100644 index 000000000..f3fe4d6d6 --- /dev/null +++ b/androidgcs/.settings/org.eclipse.jdt.core.prefs @@ -0,0 +1,5 @@ +#Tue Mar 01 01:16:25 CST 2011 +eclipse.preferences.version=1 +org.eclipse.jdt.core.compiler.codegen.targetPlatform=1.5 +org.eclipse.jdt.core.compiler.compliance=1.5 +org.eclipse.jdt.core.compiler.source=1.5 diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 83d19e96c..7a96a6600 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -3,16 +3,10 @@ package="org.openpilot.androidgcs" android:versionCode="1" android:versionName="1.0"> - + - - - - - - + \ No newline at end of file diff --git a/androidgcs/bin/OpieMobi.apk b/androidgcs/bin/OpieMobi.apk deleted file mode 100644 index 87a15c5e83805a3bb48265a78f9bd9154813cd35..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 148198 zcmdqJcRber+c%D=GpSBd$sSoHMD|P~*@W!ujL4qZL_{``5gA$8n?f>^oy_dLcgF8{ z)8~7Auj_YT*ZsKfe}0e0@2s5rn#a0l+__qfE1~!J3 zfi;Vnj-!RG4a+kfV{>MQXJ&`Z7#Kcp@?`3S(V|9q*+jGt7#YxG=NLkRJa15-{psG* z;`{sIaECl2OmF-qFTX<7{R68#t-$K>gE)@ip_u-j;rkDZhQg%iiDL?Lhpyr5-sV0< zz>0(8fMYRAW>e(ZQYe@6kp0b<2?l{7c_Dd$&sxS_Z1n2y$qEZ;4`R&yE}OKvC5cDb zuS{-Sc9?ga?Jm2KZJR@-onhMN7F^JsI7yM1^TT(=bm-E#$`6@t?GXcxQW4|PNr7Hu zU!A4*m7|ubN&51N9*Ngqjd|fN`&`E`zk1wJ_l32tu0r2RmwT@4%l$VjYwFhpd)01i zwpm|!ZY$-GdsmiYDG<((d@kH%2&K3?9jAW!1* zaK9^fqV=`h@}z|6iDNBmn1tPgE~g4T?60Z|O4Yp+bLJ}Gb9VNizNHr0QO!nUtCXv^ zTzTfg7skfVc$MzlDI%@gV8GWU%me1E023Jr>@QzEoo1EpX?XiFD`s@J7M%(rH2Y- zS65D~?4F^mUs6?FJO6Nw-};3L&1z;Qy^Kw%CLE44J&yTtt7~R>0?V%o1Xu$I_j@EArvYg}67Yl$PmEShxxy4@2IRQg?)Bz*jTU?kQbtc~9l**1>flM)Ty6M62kelIQ%)25z+Fz<~0y#GXLUT+68@@P^ z4W7C9nVcJ&X9v&KJz?}}I*IW){?oa_7pmQJM@e?h6Hlo2X6!K#63>Xn6g$>`GPRjXD-_ozF}|oq2Tpde3Gr$a?JE zuBPEX_u=wU_ayo6KAJHy>mZBYThq3a`LBOpT$z^-X-nW9!b`Y!mCK_-Oe#pgfV|GI z@=Uj@XVKduRFP-&v2YU%Yg~Y6-K_n|&-Bbb&JMj%iM*FP-M9-`4l_Pv6;^D9#~?da6XD zu=sxaQq{A?8Go%(S2wn^4?8y-qtBz8h)$_dMrsz%7T2ex2?dr{&}^;bo*E81J$``muS!_ToMWt7JX|l$a2+L4v~MyNZ&}_>XSB?q{?;?4@$I{^ z+f{SMAKIIH9khGeaom)rSh1i$%>kFE|g%BojE6^*mjaE5?f!N&g(Gj6bY0 z{H(njtkpMfd#cJrqbXPUyWCp#!-R*f*;YcdBN;ANQ){C}I4N(zGY0Ov%r zagQx!8`#W=b?>hF(;#;6yl|q~7PeM;2G-0vR@Qo07B(cEa-l{FWb{#28i>1{l^DEExLmP6xvtp1K%j@ZBx=S0Cd!hA~_-#?ZsC zz%a*PhR^00MsWZCbllErtz@>=}GAJ|39^yf=f9k^VQo zw19b;z`XR}K3({Y1z@bzKX2d_84D3SIpHY^ z&&TjIho?6@v7wa{eL&v-BY_wg=Z~e}e=TFkNS=bEm>o+1(ytCk#d8d8XjKQ=Fo1T? z!aL-;Hb~}E=)>l}e2eI%4)kmazdiGx`Z|#vEG#qz8m_@|A3u=Kgzyeb%gJ|e0Tb&E z#)E(R4zUrG@cfU5!@u5Q|Lfgc1(A6}7lJdxSs*Hg&-$Y-Q&WDSrx{nO|1d-(j%lC(;hmC!#n1^od;iU(NHM@BdHx{M#4V5j>E2B7MOt8N3|*BS*-0 z$etmOfA;O4@BZI%bn?6Z`Y+Np;-ld85^@bevj5@l^zQ%8$IZvUK%T^K6+yE4Ryy`N zx@HEqp6Wk0W-->YFlT;lZsac~BYqy27`gSl!~;zu-7rS6}IiZi2f z)8Fo&=KnJw&=hI3Eg^&DasAVqm&B;kWlfw*`I9$Piw#84 zEXvEHV&A^~c>UmYiaL)yaxW{b>&;m{xb_ZT6}e`0{Xn==g;teY`}pdI{m?_{&Wq5l zjHoEmZvMl)_!RN$w9kW(>rd2POYHflP}tho?9?hF_Zvz$iFIE3eipgfnqG1}dv0ci zTVUMhQ$~hy(D1-+YV=)a$HxkPc7yCX zm`%Ll#-<<6^EhslO_a{aML$&1y1=41+S^^6`Nohp^%v9&i;<0E`_BBFm+iRy+h47!=U+6w z6hjvMiiFe4ETmUTx?4*#Gf&-)gj{UASH4XkJ!0IRzxQt03m*|2T!}x8$M8^B%|KlI zo9k>HjrYwaMDa0nhtCWx%bxpvYvS0Z++OxtGV&Io;^5#gkl@Xcbz`PNenrWNO*?64 zW3y4EjbZT~5BaIE2J5?JcZzV~-iyZ{_a8G#i0SDiODfb{KNEx8B&@OWu$fiDB=zs_ zEgzV0N;K1+L$3MpmC;G?OdxMDEa_j098ba?QOo>?!r}O#NgDMUZb2(Z_RO0CNBj+~XVEPn!P!`jQ+9*;R~_abox! zi@Wgg)G+?KmBXhu9-Z2DraEu!OF@iJTA_qU#M$&dwyqid~Ru}wfT5*NxF=ZGdFX!$BACb9* zg-6cL6?O|hzZ5DQ@4tIML`1{~3zu<{=H}*Czxtjp4e~r2ER|neT;z3JyH0-@0}+qW z_0|}6@$EtDVA2cXt(B?wUS61eXFn`2E`BE27vp$iDE_!};0-y9zb;=YpQpCU9(_ba zOx$UjTa{`*>?j@<78Yl7B5)Gri^T(lX8rl44%sv`G<$UvhlwS_PLf)=QDGO4XF1l_ z`9ZSCX>+dBc?cHMX}yhWb1K$iZ3g$a1+?2#YfN&k+rj*8KIsh+DJiL$%|7kE%-rhc zM+z8z&!+|l2Px1X=~20#KFMv5xYaOSk<^%elJ|IG)uHhDZ;{upUuTq*LLDYi`oF>_$OI4_#@p^Du31tm8rHwr7_NfBg9IhUX5pgoMOfA-8JW zbLV=xy6W~sPKL#|wzg)oJ!JoFv;51s5LngTUS-v6Wn_E4Jb5FBLD?!L3SMSXwaTeT zicV00Wu~D{zw_1Qn;Z26vgs))-oo$`M1M!w3JVKo<}!2X`~oKIDvDspJfs)MxSzXs zh+v=ys=vceF7=ynW^0s%QZk3=5UCZL#Z<4qTTZX6j1$H{R9JZ9DTu6<7292nR1iaf zjUV@rW!LA7J&S!jYtibj0apoX2_4-ER|ZB7i#t0zQGc)G#KnIk+V>1g2?|AxA zs%Y9qkUPy#(bCiZ9ZR&J)YaEg1_lNurlyLHjyyUi_sq(xt4pHrZ!j`STol|%%qgF{ z@pp|BTPCeCU^^+PcT*emJ3lIAZuI23DsjfXKG~bk-RT(_uxr@(I555f&G^&DKhdK+7S`vM4u?<79!N-Z+`A}{LMs{h zce{36z}hV+U%SV2C19y^{KAlRyFk8LHa3>K$OCXJF1)D$4XKflR|K|x>NPhuQsN!& z<4RLBGjRooe|K-M*zB1Tdtg*DproZGgTCE5Ycp5k-|AD`6GNaW zEq$Kra0gw-idf=Vl93%>SbL8XBaj)*{7P0)MJ27cm~(P+^6%jC8g%p0KYn~gxst)g z#41j?~q!Umus-Wc-I> zA@d~^sgDf}y;M|G)HJ>dyN7(&af6Rf9X1f#BOo$5I^E*Myn6Z6TT{>sM9QDm&rmYY zr#9<%B9_c~xk}~2ORtko64BJd-FSjtuC*Ng6Z}3qJP(W zOb}0+uBW>jjh!m(=vWr-Fm@I(G$(@(NhvLT3^tgOH9IscZ1cyxi?hu)bFZI_h59}? zMye-b(QSq=Rs*!VqiXgIzye}n9`EkpVxyQf*PF& zY%6wbTk5Mani^0zf^Hm7P^qRb|ZVd5HES%E-uY+WGy`_UmPpznjwK zKl|QK^h&^e)84F(sOk;c>QBeg>@MQxQ268vmcUvg%|lsP`jd&KD!95hCq&WG}xfXV0E3KRWzlTX&wTkrnS`1(3FMiG0l~SH*_hjt(9^ct8mW z4G|0s=7@nsLsK`=51=+6DjA81?kDpv?T$4`9i~$Ikd`(dB2M1niF59+m;`*akr(C5 z?D@#@VpdYE!0;RZm?qkbQ>SLAWJ~#pngov7jWR=HvvS(Xm{%bYbRYlUIg7Dg!-F zA?R~O9yYSMwe>oxzOc-CdT#X_g^Ia3v(B-atq7(DP;2QM8qVc?BZp{^;N)vc(DK!< zh6S@XwRc}t?|fxxHsd5fAw5yLf(MO=iXy-s`yQd9mGP3?=|NLd(}|$?$$~8k45c&& zVf>h#{hHJhKs0-Oi*u*X6D|WQ|+s7aiXsUlkbu8Bn*XijqVaq7p+n={_^v$S`>|IgJ#6(m*&!^+=XsrW3IkKzZ zY*>%ilTd_mI3*=z=J!jAUcgXik5>{s1O^e13ks_gWmuq^sgm0(usui<+a^YNEWI-T zi%OGlnB^rU1IS-&$Q$VEqfe~n9;+r{DZitmBjWl%0dQz-2MGqG51_1;G;S5;M=j62$Oc6Jttsm@a4 z`TF{9Ts&I2h|edzGFWE)E8if1myb_LL!&k7G`nS(F=r;kQ=qoLN-PpQzfdL}%Xz9S z?6irA35psI5<44970Y7#mKQEuFge)U#Pt!maqHHkY6N>CC_I=CBwnl3V)4Mh_pR~7 zaF3Q(Q4vS!v9WzX*!4*6aYQul3q9iV|B+D zftyPKBfu^Sqjf$xt{d9g*@94!MRM?ztWGxn<|%Fw1P*so0y#+#L0~2(a9r)%{w-ai7SX85tR| z@lVh9<@Q0?t-G}eF`)5y!)spWtt@`>izHX2lK~cj=+8HX&=8Z7UPmJc;`6kmlvMX( z$p~{DD~bj$-tExw{Q2`=_vaTN@SkdnjexKrFc42>{|{w-)*VcJ(d|Rp^<#xPcB? z=Ani}TEVYhY9gpGm>7=N7YKzRB;U)d*}DlqEFjiqILsbKJvTQu)?rMzgvz)`rVt2tR_HMCW;~L6FR~1`>;zpLu%NtN7p#eic89 zb#iu|Ty@Yd88~b3iszk7TY``_I1@<8&>iocpZK{eOmeoi9Cy8&x@3iJ<@QOU6W)W} zB;hoJz&IbG6_oy~7%4hHDmMfKG@ZAXUbhUHdoVf+;bUS@5+l=+dB^+V%a^;JJEYL^ zUhvV*#e*)PgD|irD1Bn4$Df3Q1^3bc(4$V3iUtB^c^}j@+f8OaNOdeO#pXlJ>^sc) z!nxWtTIMC{VBoRYzJ`W|-f=s0Aro@dNRv(YJ62oksaAPV6Bz5w+{*W1^s<-g?}LK; zDzi?zKp~j5wq^xW6p0a0&Qy|?mS)4dcjf{qB{I)Zf|%Az?G_?Y<>kJ;&G`s0kPt_Sm8HGWAp+UEapOj3ynu757#L~yZB>O=5qFkN zAFA)YP*rTX!}CcyNg_VNXQpbl0`VOM{UH3{DmGvb(Deq$xQa}pz*Ild(#io74&wr> z2EoA(&@G#-1yw9e1S1S{#7;1oC^gqw+$`IT%{O?|#Hwx}eJdi<LqKz;mhX>%wjmKl!lq^g)X-WG7?hqi~2wk2El!z(ffzn zH7agyLU*M?geemRoVU^o3KYTnK+NgQro>fdSb!vbz_5S;TziTOYg^B0S}xx7dPL4- zp1^9NJ*sKyaPa80PH|KGK#KR;{N*^J5Q~*J*L#Vm^Rv~89v%mur%&JnAy;qLljqOn zKxZMy4ZI?g2dm!}FQ5)$*0Zz2ji?=^9T8nX+*cJw+f_AMj=`JInQxOzhtM~D>n7Fi z8%7SXTSLFq2}6)GJdYch32^Ygjl&^ zk*$TYwe#c(&-d|kXx`u9;#wEpV>Pj`Fp@mF#(L*Y3iu!hzB@Y=#LlJ7X>}MXf^Wp~ zaKAvtD@rMxb-DKQ;~E#EtrpD!wG5R)#w44VtR|n(ruU;e*L<+d1Okb6SX;7`6uMqK zRNXHnEql$Tnr39gE2+EWJby84ZIZ7pD8-KyYjIb*vDSW&mtj>@N^^tx1p*rV9MPn4I+4yCJxe@#uL;9IZ-IynyW44}A=I zOUyiLSDVMahlnI?iwTHixe156IK*T>WKd7)zWFPhdz%~tUY{s6W~VJbHKIw$HdBhT z#Kq`m2;pyoBDEsJHsY8z!&;OV7;b^}R(9M~rmkzYAmJdK0Fpiy7Cxd2^Os8%hGa7M zgS3M`+ot;Z-oh}XqN|e>yjiQKSeil~QA%1R=@YS47{a(z&c@GA=9JyrT5yWF)Oi_K zih*0OF~Ysk*}9x9f_vKh!>wJn2syj#*0a}sGp5jiL>GZXQ!_G*#2hRUHSWt?wT1=YcR=L|0mh1bzDpH&zuMyzvCu|-79(x`^~o1&uXDaqnLhL< z#R-^+ig4kx_77TJ zxfN2dg1g)PPR^Z7;`Y6z%5@nqnx3dIB!k0iAGBHj`wFg)&C2Lqz>d-YQy)r8(}pw3 zX=r4D>p`T6fPg6&!-sY2&|$CPj@`;-oNs6J+vDl$%nlYvw4C3Y&0e;;qMcD+&Vlqr z%c$+Eqwr)ukWe3!E!CIywygi=HiK=`_5@S4f}zod%ct0Pv&)MQ-YVIs@vNzZ z^B>*)z~mrT+**E7+Bm2|Vg6&eYGevOVs$4-Cc$;zQY(A_kP@sepWVWbt;K<})L2Mm z0#dm0kb*$+!4qu#i*_)Ur&d-90J`W9A(DT(7T0j0GUd(kp!0lzRAfL!1XpW*X@Nnz z@te%Ca}Tq2--E=m@hK2)yk?v+;4^n=F4D7Y(zFdwh}!=!SWv?tX?3?==3G^HsHyZ# zp&FVD$?8KHA1o*jNX10lRAJ*_4m@0WDRk`X@sk=F8VW7P#oqDR%a8}Z?5J%y5M{?x zQc<}{PcQDgwIEOVSat7=6_I{hwyf2>Lq=|%_aTc%868#aYj|=RoRFcQPjCr+Y5lUpzUGf+ zybuv>XIGakB=yF< zLPc( zM8A1tOC4@1XURb_2Ha6^wtA8Cwz;Pt+tAR^uS&;){DJ}w(_SX5GQ7WdabOV)xKMB^ zD3&r#l^5~6lf1%%tyZ4U+vnT2ZsWyh7U;LX%>;8YnNy{>l~u+@tIt3fE%$?uA%6bK zyDVdJTCTy&?%w6bkQ!mS*jTy4jf>JE<(Has!)_HQA9{FA=h}{9RX<{lvFX#aZ-T0T zSajw7T8mUvfPz-8N-UQ}@8{3%fOi}yG*iKUIr5V)4p*s%g=K|_FZj)KcqcenCuk*g z)4DO5K5S}@?DW@>j{Eu1e|$On?#8-H393es1E&9IX>P!vl2{zD*kSWx8>jvVPL)C87jlnXczZq$1^7kg6 zkqWEWx&ZE>S|gssz|IK2`M&0iZTf<0m%3$si{2#iGhM7*N96PrS9kY zdT#_~LoKTXB*w4+znRtwN?af@pjtK?GxAuNKCFg5o)im&Cha*yO6s3*r?2By6P!)@(v;yXvp(RdRBaLL zg>$g>uD|`QnoH|kPv)c@I}V=)=d)iaFaB)di{kOP?w2BA<;I51({qGoY4sZh#LLN`> zZ)U_IPCY05t7*ieqsyvY&8hlaYWormS3t4WIb0_$X5FfPsjsg;b545)>#lc4084c` zyU};FXkbiSTsKIu?O6R;kPWbSB4whG^7@#b{v(KtZ(=fOOQV+fE=rZJSHm9{s1>)W#gH-L?lxTBSgTBLandU_WXxLvcYaWPsX4MG z?(>CbU5u=Pi3MawqUfDB5W^#haM9=;7eRr8jjlkK`cI(0NNxduq`a0ExrYW)spx^M ze0#hAF&P;xVt)5hHwPtN+f`A938)qaHad-F>J&GJYA}c&VwHWgh{#;KqS__E)~|sp zgLiX6@1FZPo%Z<5iK#Q;BQNxKReD9V$jbw`bI`Jua5brpAVcgxp2zSdD(h z%+{`nryNV%se$4iFXRzGut_fnZZrF|Oe$Dg7a)NM;BrJ@Qel&~3R~=*N)~v|v#Dz0 zJ4Vx)dS)3LSY0V@*0g?k>0xdNN7)14{!{>foU1!sY|ktkm0YV7)N7LK%Z0)?J~%j$ z^LfhJn)l^Sknlf1@3;?{_aTu}nE$qJX<@c%Aql&>x;kup z*=<#>4b zoY=QDM>XH5O-W>T)2eTHcUb1**;!m1x^{~N{7jN=qWtM127|+r@cdD#{`@)pXjLf+ znd&e1cuVG^kd1+8PU$!$!zL)0W0dehnTqpffFwkW%22X&Q4r{{I7wbp-Eqk zW>($(`U3Qq$#uJ$>}o~6i2N0No`Bp})vxr6TjB?poR^$O8qUyvHyNw%-6pTF)D74- z3cl}lzK{;t7LA^grqI@x>cEt$jzO>d-p6RiN+vIi3D)$a?z_KM4AN(JdN_oCR>mX0Fbyo;{vSO7$W z%JwzTR&|T2ucu0=BzUc-0*4)^$pF_uF1U#mPoxY5^)ATdc7Y0CMq#6{32Plj{{h|_ zMC>&3bg}Ba8@R9-k93FLSzTd?_zT>!v~l-nvO3;QFg#8P_qlizU~a!*Tcl30m8Dps z+~>5U^KMri`_Q#>uWshN`8Ez2E2ph~qkcgO3KTXLWH?K%YMK8fgtHt8G$YilV!*+^OFKhM@$Oyp$ypH0|AqiJM+#9tFuTR2s(FBzV>X9os8 z9`>U-G@9Puf{mtMf5h(fqMHZh3KbOCVnf5OwOx!#N}>`t+F!@^2);%{^aIj{G*GUA z@JQ?&i-?-qThLn=2VG49%U#eAk`sjeDl6l|bc@8oZM?A7B{RVP6CZaxFPSR0M5@vk z&?r%jlzI*)84H~@HHir&uF2`99SH%PAhjjRT+ML1_{dRuYmpM=LJ3X{$Qn1f-s%*- z_+$5Mq#Ej${+?eFx0Z%7tDLuyh{(JoR*qTD#N;D5-9p=W<%d)Z-mBLqNP56+Uf#IS z9528!mBvhLn90oIgHxWe53aW31|?9TToUv0{ru}w4{#Z|hgp0C9b>K4#fn1TE-B89aq_IaHOS9T6!_)nJlwGp!gUsl;?rZM zld7E9pSsD3rZA_;2o)68RRafy$6zW?64Mb)`qbg=A#rh8b8{xo`tyAhP`En$Z~3d# zK{>;rXT!d%o%6M<`ZCe9&b=D6;o2}cUJd1Vp79nm%W~L;>6LOZ8w@L14 zK4D~HVtOPl{!&Ee*PDxw_>+IG`&du2CJIZiKYzNBm4Vl{iAhp7XQ50QkV95Ij~kuQ zYQ(DMTfLtvzDKuhO&{VDAjFExSFaL?5>)}JL!dWGBR?brABn)xsPwF?z>eDXkdTn1 zl$7g8W|S4pSt(h^NZ8#Nbd=oHek8Q^Zk9SYm`jw+PyX&ibhA1E&}-Cu}3wvtp(dO#=; zeyj)$401YmpESpDTZ#znHpy-PrAApWAy`?%xwf zVc%|ZuJl5$Pz7G_9YGSJn2OB*B+&QUMrM8_-NRmE1agE*_1a~Gj&K@;`MbSgf{ehC z(z}7(7TF<70>7mSFLyc_v)6CyHXZo+wM|cV_w?Y4L_-ei5>{$khGN==z1z0E(^QPn z9UdMD%7o8Q9R)Im-aYbGZq5jQ(WFGWAdBAm)e9h)2Kn?MXLTDUGBk;YwlyA+W;W?} zB4H4a8;v2Cl_v9U3|r}?s1!Yv zl6nMC11yKl+Jpq8n=Pr+en1+%=f@970>j)soG0N#V;k20{2Bc>68Z?FC!=6jQOM~6 z3kWedwNTa!^>mdc9Y}1dUd%UY4{MsDBM>brP>%nTd~9oPTF;$rX5&^rly&Y zs)-CL(|I;<%Lf+Yl&ixELh)|!}{oDS7m`d`Zg-d0*b@Ihb*2tG2qNA5BUL&!JR)M#U%UP*4U7t$37|o(Bso9GW!1Z_2XB~U&EJpF zjDg4&AN9UrX4q(AJ~-$d-Z@-c8!$kwOF~9@j~~g)CjleJSXWmBa#7=6f2f&M^F<8| z_Q}p6*3lGH3c6c&ssgsNoSRz>R9@K6Yz#ZqLLmpr9LxZvR&|m-r&NlMgj$Tcla`%l zW0DcMTTe2)BXl_~FerlsK*z_Noa#}xVMq<<B}nVDg@ zOZi?(M#coD2)xM@5a2PV!XNr<8Q>A1>NMTKnus0?^VugL7FzS&uN%srzSH>W=UE(l zqy0t_z|!Jh^N4+u_<(bj&&l;bTDs@`{QyLl^u7gI)*YOE8yl+xd^5Dp9d7RQqrKcC zYLsXeR9v1y(d?n5q@uaG`QX%>=x7GmJBYL_<$)0*JN+*lbY0R4(}VJT+`z8e1O+eg zJ;?bOuw@SzQ+0?D!EU~SsKY& zqC|bFs|6831b1q=yPyE~Dl4Z#E;=>HQ^c=*nq;Q)=NA=y>04p6x1)s7%3%lZh=)i7 z27a+TJ{q@Hcj5Cdz!-N$Cutd20A1Fbw_LO4u1mr4PbO$!hYWgMj1(qLe>8= zVSOK4%=`D$&whTo3;fq}n1mu4MA~j?4Hs*e)t!7=&5JD>T1oo1*m1t!|E5Q@w!Ur) ziPrYUWnlQoLAe~N(>B0XhIpvHjU&&n?QQ8FL!nOK*4~HY7!^wN7R(uPXLI07VB4&C z$H(zC=)xp`0|5l&F>0_RSD7INmUoJU@s6X+)`BCORMxR6aDiv&-mYmwR_YgqkDeZxxtc33>8MniTr_5|upV z5XGWRUVMhi$k6a(QIQfLYjChZ{jszGXbP1?JWCBiirp$k-Sh4jbBT#vp|7kd=tIXvTFs9%V1)iDzSn))=Ta3ZxfGtNwaP;@nZ%`Gj8fY~5F#Qhs) z#pdn#mb*-vpo#?YbTnZ!K2of-mEyypCC-}Nq{~q6Cn?_aO87Qw^AR`{0LeRI*o}aI zLJ`qd58USPu&}yVnm{^w`pu0l+4U!;^*&En)4zY0SsbcR`S9TbIQ+njJ|iOEOP4Mo z5rqsV^R>FWJIk@&hcfS+4l{X6)}!PLXs%ONqRB@Hl_)+Uq)NBA-Q8WMQI9hlSApv) zzrAp)pr3!7uXJqu0y%%9A)6l`f=0q*1+RsD1wx(#Sb{ixIn-?q5zGW%zC)pRhX<$D z5(LC3OXD&n2)^;XpL$wQP>^i$PC`j3g4}K2^2Kh8wz89xO%^6I3(IuB7k*+vK^Phx zweMPUIH`SjA1r!scC2HV1lQp6Q}jfHB2w8+ihQhMIPva*@7jYJWbS}PjV5!{&G*4voxMg4nMh&`YfPDysJq?m(7Fl;47WGS0f|J! z#5A34pw&4~B{-g&s*QN}{t`_@NBal$JAFv|xQS4k_kQ(Nr>a7yJInUm zr1Gl|f**5%)(??Hhkps7nmck&S+_Azqak(j%`x|Qn2ez9mSk4 ziTRs0!`Q8nCL4KND)f1Tw}9|k<&SuyIl)-e>hAwA<=w0hiYhS@(5WxmP7M%iXZBrX z>atD`x`nAa!z? zhr#|d;gRN7y>ctK1Ww|72y z@6VsjtpSTna7&O;vf_PLsbly63>=_3{6o!;xNMi62Wbvfj3(BHwu#^i+SE<^7ZcJ3D)k?pIuy!2|@Y)%u)+bY0@`uon0n z^JX`33yWOHNYO)C57Zw{fp{huvQ%w^!p_`Bf5t%|A`oe_y8$uq9|DD_3V3S3A&irP z-PeMG*lUVIFQkq}uaABZNCJbPbK<(+w)!28JAjG(UH`%p1fi(7_yz}u5)@wEMn^|? zCQ#s=ww?JwRki+|k1e+C1_MKMuWjHe69knIrj0eAOCLZ8*9k*SUOzoz)(aQ~2#78I z5W(O-XJ_M~J{rAScEg-Hkccb)KxjgUM4;WW9F!W0x8MB#5CXdoj?-jkXXp2ufkTd8 zQ~15UTL?AiXTz1M0J|YH`h87Jabe|momz=G*N=pqMtt18NhUK|KccC| zSQeuWgETr?6a2A(}+RLp}9jaz*Om?+? zlR`JXKcWrKe)CMZ2&fS^xo?w(d~4eKA{hl-7RU9ejN)Qt$mjNgyG-4;j}v^MW>Irc zeERfhfX9swmT2EXT>=g{nVO?KT1GdWlGk*W0lFavy};to;}eRA`pF3!ihl$#(Z@dn zrB5rBVd?_*`(bI@HwdHs(#H`l958~~{mb!y>a6zZi3h^V23i+nOF#=DLhCBGorknQ z28bwmu}cV&!~)9KCG6+dzQ^$-LnL>9@~R?0eqN^yhT|TCJ~vvH8I3UeOVf;b>V!V) zH3Qy2q^IES_k}Q#klPA*K-i4;;<^tkj-Fq?K0+b@wy<%2Q)agP;%P5lhm}MmLsz8M zAF@FW3^f^~s*DLyHpyP2d454b`Swl9y=MEql(j6>s-m zjnqp1{4@a~C>?=#Xn*K=-TAoa4E}GvNdQJc3YvdEM{4Ja)ikpc6DgqM$v`E%3294k z4A@6JuG9#J>$&ik)fF?F+xANuZSVM^2-u{#DB#>q`Pi$Qgm|an92ooLd>>M-em1~~a0vi& zKww6*Ba57+2F%yP}#$IQn<+-(SrJ2R65*keGKoP+a+iido_MJv>)I}OYHiDs7m zC-Aa>cJ>hcnNUJjHn`k48NB@RaMi*cJdjT52W;vSjnC*_IT#YZn6IR;$62gZi+ z4*STH90;D_XhEFUwNV>hC_LwaoPPw9d2nz5-5?$X4ilaY=rRl0qCn++6&8%bt9SmUSGE=n)IRE8uq za#q1JK?g`vK%A6^5G{y8NN{rgm&m_Z$-6FscGn{|TG`tHs00RFjHX5$2S=XQJS7F{Dt z6MD|ZHi_6f&wh0YK9jM69xPTBJ@jf3Fez5$&X||KL>TqvfCO;u?aIn?s8Yug_-!9u5W|kXLDQCd3F~k_4U31FbbFS4VtSfjov`3B6WC&e-fq(_ zu+6~CY~GnrXI?VDU2{~0_;cS0mhoG+ZfQJqzX%nz*d>m%v^48jT2QQL(t|cD4Kr$# z#$;vpjrN^H*@U{l?GRk$-@kt&$>kdoPLW*yZ~<=Kv~9Un!az-}+nF#9-eYf)#qF2} z!D~DBs8N4laIh8U^p5+rzA@nKf=XDf0T_Cs8;*7}tK5DgOCiL_C;{iSu*sh2>gsO9 zw7ZBQG~9fH78ka!>l?FOdr@w?R}aRn*8Bj5pBJxeZeI(EYLw_KI=<7h(%}BxHT~ouk*76|N73z1 ziCZRcKor1SgdOexYZfTTh@ISk)W4~&E_M2vUOB@kpG;a;xDcH@3UGojiSaOlqX0Jk z7~OZWh`#Z)S?dW1QVRXy-(y%?y%v%CbZ=u8+JiH>NEHp*Lp-M=|Cd$4dK>xACCr-T z`sID36cp|Lr+m;JEdqmStMR9x$%c0Ft=VyUI=a1-N1wMNnKeHm#X#gxt8DL=pNn=? zJ7WQRzc0F_!|bhV5~`gC&SMbP3IXw%!5ig3BW=b^FbAijF7AKIS3?dxLL@m?JYcQ} zC!JG-zQKZT259e#9PPIsnKi$|rp+iQV4q3-j72Ddi!^{aUiEUayz?HKs@Xtjetlh* z3h#ovynOk=*1+cedb{albA(`jNMUmFJ)whH+2bPNRb~xVCBZBTY!?gAS`id373*## zvGK4l9#wN+vKL|PC~|xhIS14(_$MopNp&o2Iz2bHZ{+A;WFC?Tp+n|e_nG1T{gu}~ znqqgUuwC>D7tcFtj$`9{y1Y30V%(L=NJHb5==B3+XA_Rn&GC)w1_AqyYc_Zp4)_|i zlOq`;i^^4BIIR5H@b>N7Nf2)`<9`0uT8eo&wi%e6)|Fp)7l`M7-bGW{j}5)$R+;Zg zdt$@71D0K7WUsemamkhLhg)>4&aQHY- zHuWbWQsuu5Iit>U1O>ca;}vJ{jwS?{ejM&0M~wg;K~sP*ognJoNTxV=0JidCx}H%v zgD{ng5HMx(^77*NLDF~PqJFu!T3ca9TJ~Pl%@_KarF=`hSPIb?D32$>|8OAT7GypB zeHJ;2;ks3jfYW+Mnll`e!JER{7LpLPcYbQn74A6QiveP8f)thLXh2|KHxwa00>=$G zSO^*(c1Q~LXD`idj~nBf2t*lN(q-_P zESpNY1`*OUZ~fPA-{yy%mwO7@1rcwi$`lD>0MF=ov}fOV_k;N>o+wNLqu>WxBZr;MHuC$qz;l4JX4;*KvH~AGJv}AdTmVoO&&#vt&W%rah@jS=2W$Lru;;joUFJVrC-`E2 zXUCx}jwdW}HU0{-MtWL;tJ+1O{ZDWbkM3ag%$YNrNJU3zuOqno=g*mfafDX=K{ARv z$vq+3*87d|B&@uRZ)_>feOBuW@sZ9O?`0EcSXkQW=f9%);Vf+q6akO~KXMkwW$pel zAdurzMF#^l2eH7UhE8Ibad)Cr#ZipNF51w2Cyy{q51{ni+-K7y#Jo;TEn?c2qXhp6 z0URBh50j>Wob6^kA3|3F5b$>6n|+xE!UTsvCk^OE>w3!%0N(M@mXu+LTr)jxt#O>F zV=p+c8>AHVA1`>5}=t>r3W-k<&im-Z+@Xb2fO*rZh+OHFW z^VPF7M<5zlhnKHiGyX-=#g2%yREy(oIO#MAirVj!E80*W3Koz}Mz|ixiI}nRary%u zI90GoakNUYx9xUh5BSDyG{Lq^1BlSm^%$=DQyq5^yU1FkBX-uy*SS#pdkdN1i=dxB zA14exCw((qR<;hLCnew~17kr6a5ktKlJ;2*cFRI?Fc4=tv%~LF+_qW=Fi~6!5nW!2La~S#b$JVPZ+kV&KxM9Fx@2JEX%au zHqZaV+?znv*#2$9R|D-xHiZTn=uWs*R7#qqL@LUZMv(>@D3T`4#-iMk2vMeFZqTGq zBuWt~m840EMor%1w{t(w^M31F&-&JSzxVyV)_<+rpWWX3x~}v54ae^|j?@45P~Ao& zqvw~kb4!}u0F6rZZhuGQVNe-PLfIHM;V3&85$)oMe@agltzmz4>x)<0_oUf02J(V; zU5`YS99tmksYuW5U5J3W?~P=jmzM>}DzG|9v;EXk3ol6&EK`8n1HX_M+{?neOy!Ugq0VZg}d%iAAkZ+JISR*!bA5OG)9rKwl%S zU}g7>P`j<8@2$N)W$(W!sjsu??zTe#T_KV!2l*t*?mJh2_QCCVe(?l^&zWJLtx~N* z&hgr>YpikOzSt-2`oINQ>iW%_q~p1D^{Sj6m+{dlz<>@iiZw46${GLC{W9}Z_trUK zZ0UK67q26h1^6T+ua*1z@1tgn&{lI%&Z|G>uCZyB(~W!iB-3)grhKB7p_kWv&>i{3 zxfV!E>w+Yjc;3HnGbx%`c8fXpkhefQevd^`%0r>h=L3yK-=c$rUtEG8A6=7~f9v37rq{)1JJ=APmkt(4qgQM(%`vxL^ zDNhQlahpAV{wlCYWp~E)^L%i5OZxlX_Nw+*%Q`KLjRo)sID@Jz}P1bW`NQCsFLJX`$u^pvQ{ zZL4b2l=lwqTFUqFi?^v&w*!{unuHs@zg$aSzitkdZprndMD`X|19Q)o%7V%QZ=PVT z^b6mYXAJ7VK)Jw8;6DkJePzq{6BCntQjKSzg%B7mn$)G~i1S z6MrF9Ic@s%w$_xycecNKZ5RCYSC|eXY4<`7QXNKI^MSQZGfOwrPWotMq}_;=)N>dX zT)L!3B2(*qwc7_3(sVA^kG;4%>zT@%zVW)omKP-QYUXcU{N?M{-HA);qe3Gh$U%Uz z3yJMl=<)KExYJnNV&& z?we!3aO-8=m6(xVM36?Z8F%bmR z>`J57l=Hr;YzN<*#)Q~FD&G)#MY+(Rd7nBo#GF6q3nm67rRmzFS18-=+%Zj3(o`;=k2P_kxtEu67@l^%fPtk=OjV;yWR!D4Z-~xH|L1@xA5dUvPfee{ zc=1WIpnkSMy5~j2xX9=R(Y%{?Ucp)>?&aM8MGX!7O1{jY1h5!ba!+UHhne|)k4vSV%xcr&C?uN&=4hnR7-6l=e+=(sSpqO<|Owt=*U z>-pXgaA6Y^^NZl1(A(i2xFxV#H82T?CAV(zR$ABjp$5zLBF)P}KK#$5?FEH}q7Rs1 zCyciSX1S4vyk-tNbmluwIFGJUxmEr!6*|7mZ#$YECMrF3J*Tt-4}mK%(Ehe1 zVXD-lR3whxZ%wb~yESeO>LG4fl{eYCj+=#4-@a6~j;&t9n9oJ5P8_UEAu*7+TZXQ^ zy?to#g(5KoEUuW{)~)3}o%X@_&A4sQeP?y%4)uJy_ZsxHSRHmHXGtn9T5|fAT;fy- z#3Gfat0zsI=rAJ1)&aQKiw1WyG~vS9@6anC0Ol)w+N1NmK`VHGd3A8fe%Wy2AC}D! zixn5IG!bJ5{a%s?Cky}H8@B5m9c2#&>515JKH*|XdpXL~-2)fiy!2Yj#B2j$ikLV( zzg`F0kXkJGLjKtI6?d+lomOqc?hNS-VPs>TZY}@6M&$g;xWy>y>~^33A${yzz*(tJ zAypmGjl+xfWZQ2}MZ087B_gV@d$h*jOEM3u$jnZC`jNln-0l@{+QI#uHNo70uMl>! z-6H1Mv?naxBRp-|QzIT@S$TOA0IcZ*Sr;mzFk+2Mo+2(TE?o6Dt!6Vn`SY>e>n7?B zizXl8?m7)6zkkC-+p@Zm+PZ7EZ%6CcO?bT6I+nJglylq`v$!nw*QO@Vf*>hHNCEsi zTx~0=@^ovB}X<32xd+_8i2>7@WB@Ws|U zpwhHvHlMG+&Mb60&Qg24SZ^hT6Q3$Ph>BRL#2E#9aI@GVSf`}!qNN6FsSW!2yceaU z6zK}s+pPNTiFInOWN%$A${a-NZ9p`B>Ll9J@@zINuwAeCVAFDXWvD@X#<;Kp8K$=u zXnyrcx@-BtY&>fbp6uXovvwLG6Bt>~W*c+1Aa8J)Pp2*x{c?34rDKAxPyrz@M8+@O zlbnlTcH8s0i57@P2lG3}-u!6x`F-!EhVP!|m?g&uJufM#ATE}F(*oOaG`{@20fqEX zb)v;~9k90P*T1@C>zagRtE74D)K{OD=k#Vnoq4u^^mw@w9VT&J`qS8|d{a@i^!{(J z4x0ZwIywIH1IxdsBM=N!C@5^Wff4i-)Zevxt9Knfe0a9-fBF&&EeH*Reb}v=( z=%GUmTgP?HxOC}~7u5gg{?;wncx#*Cx&dBJy&oLcz3#}&8K&!4JR(UUjFz#UUa*8u zJr@y;EbngPKWO&`UQtv+>)aOSzq3{^t?1gJ?n%k}b1=}gy3A;uY^_LXFE^BYyDztU zR)BHA<;dg59lwYoeZD{D{XKSvpWL?NRh}2u+EiuCv$=tNlD)q>VnQ4S{&A9`+N)5ahO$s0 ze486EH*Js1)u@U_krPRI&y~|qB{8zAw{5#j&L&uBE+~2@OrAVf*iX)YHD!X2D(@%n zrsCJz(}qr6T0H6Lmzx`UzD>Jp@Qm;6BK5&GW2LDtM)NbdCVsMU=*d@7#~n5lP}uPEJgJuczx;WPJEy=&QK zE+K@_TyIJfHEOXjvAPTj-c|UgnR!gpHpb=G&yq+-yITI_!yGY(=Z(hGUI#$=2QEuw@HU`)z|dAHRAid z=0wGeoMpQ+EbTp8xrXk}eKl**`j;@X8Fjp~X`4tmP<3$ku5?tVlQEv1o(N~({ex?kh)b@Sxq z(!A`IWN*|}IN7%L#Qi&WPMGQOa<*Aqg5Huc*=C)yw<<^1O?jT#xpQUAJt;oA4F}BM2{H}`b?(R$xCeC2frnn7h zHmN8CP26*O|AFfvx?^2MU8(m=sQyQZporS}6o0Mdex^5rs*Vk%s#GzaQKvM>q<2f<+0vb{&m;0_kX&X+k= zSiV}!c`(EvepJfU>+aUCH+@rPzS=Z@^Y7gakE)i=H~ei>F%ykA7ca0k0pb&Y?^qT- zNgOUTx^l9Gf=Rg1ET{87N>Eu|KJm|*y9R&F_kHzZ-;0Kqi#Olw9IiOua^tjy8+?9@ zPr&}gf2g`{1K3`KkHFzY=&%tdQ8C@Ig@>e%J#;H~YM;J&j*zhCfv~N+H@Idu2VFZ3 zNK$IkLYwSOz{crLzN>@@?IxzC8`rIyI+v|e z27?F7J6pp*JSJ!W*X;z>mL0c+BHhIw2Rqm3Gg53tb(WNczJWoTdE#K~pLUt|ZRzU} ze$Kn&HZgv(T3R;$r71>sX0KxKKraSkui#cHhW%S>?Rb??PPYf{adKQz@7;_iXG%U)=m@n(@Q+1qtD?*b#Pk^R`LLiNYY{F+a-A8O&Jko8Zhw2uwWx8` zUTZleuaq6w9*m?l2z0q!VG1psqu)C*<6SAG^>;npsNo z>>%>L^!h?}mQoloxji51Y;kdO%LBD$X`-$I+;Y$n{BtRYk&+(6Ew1R;RoQjQgYJGDBU|Jc-NUWwggl;N3 zJUe<}ekf+>OXf~Tw)hGHiPvC{GtFWF!C_U$Yx!p(%+Xcoqb`Bj-h>GgKx!cZoZc@s z3K@axYkZ#-6%hi<%@PC+@g2;RNR|kKrQD)LYl&RU!${7?L&uWX2r2@|Ddblq*V&kS z*6j_jsNktQcz{}BLB=l#Y1svcUi^|>@c@7EO<7H^ zYv6OK`{2$8XnYX@pC3XSrsHw9y2EAXP7Bb|1_uX)XUs@J>Fs9A#dH>Kz2k%-Jxn34 z;F>^;2lHi(VrN$4@nyj-n+xECMTI-__;urt7J$vPDUf&J6cu~^JfUC(Tx(Xtl9xX|kxM!ZCPmVP;1@z$0$L+3-r_riY_g+P=8HlK| zva+!tK4VSce(Zzs8TtN^{&M5S)A+aG(Kw752~MM$kYUeODM{Ij2je-7k6s?;A8dDCi*nb?yINYxNQ-7Ki&bb0t~-c{iV|GFVyX%ne_&>23cH+- z5TeQ3WM2iQ`rVx+^<{;DfeV5l9AZH1f=|=Lcn6G$2fyvmzR}fH|8d_5PC%>|^1$l+ z{(S?;FJSN~z*Gw3A~1B1c`%_j@pu+mXIUU~WcmEKM5D<;2Y4mCwHfqr0^`$5@gXYyT84>JAkQ_!`&K(^c(k+jnSni>^u3 z(v*8$h)_KC>lUDIm7(!@08vA283hjl1E3HV{++A_9Yhm2&ao z#ULN+#F1}1z(k&QKXdY=Nu1anq~rDL=k{|DF%iuOLFzs3z{;~VtF8a#0ua{?m9vV& zGXV@oP=I^Auvv}lAmP^qyRqg{mbBJNwJA(~<(@~i>frQ&)Nu>D3-)pP;39(zw$p$| zN)8jl8{(PYzyPKxZFoe)$f!CsNt;vOU3m4ey?6KH27fZN;`$n>nzYobC7Nh25I&%W zCp$R7pbHKUEKh+hiCg%>l;C3HuN>9Pc?q3i2bvWWNeJdBk!*^}Ew%%}OP2Y3UyU>i9@Fy6icDc_HJt1Pn2# z77$B_QVe5Q{D-dQs=lEiT#7b<`2gdvN{rO~e`=5=FkD(Br=GFN^*ckb0>c}FJOgV0 zo7$srgS{;}Dd@sfNy#+8h=j`y|LV^2`}Om(W*=4>VT9q8JH~TDI7<&U2DB*s{c|X% zB4HtZUrA2BOK%YkjUULC&ammC6Ae`JfGULQK)1Y+zUTx^PY_-( z;`88Y$oXwergjcf8Bo2JF2w>xC26jw$Bog<0~j9es?A!D0^q>wE$e|ApuB4x9qQZ& z1yk`?SRmb^^=k!L4L9@2{(i;rWxxk$nPWyzVpPz-zSm@i@<4RK`7T?b5`{FR{JiD? zz}(5GgW>9gCZ&K2{-KD+L1yK3b!jvoseZVNCJVS0Ty|_++{%By$R+GHERc<=Nq0W% z1gLX}pb$Q0IFyrF81vEXmmz{d1oHjybjI&(O7XXED{^!H`}RaGL+=T;0MZMIqYxG{ zGc!?3@{+|p=S$jc+on%GS;#D>a0~~&B&0$#|MDPjb8ICk3#%+IBQOJ~DkrxQTm<$J z;G8LfoI?Y2uC}zct_1^*ye5W+hi{xMfAZuBN-wLiDK`_>x7rv92R!4RH>(w#0nF0s zn?HY@kD8?Y*mIM9jFJN-D4dlLigU6=OMx{ZATnA(P=oW*H+}4Y!6)&9Am2nCvD;fI z9%k#fm$WWe(|CAz{`IcM!d{Ilg##a+d%ZPh8o{uqV%kiEOeEfU3JRupSSV`|Q)mUE z+5lw<#?a1(UdwF}Ai9O_BgN3|w8Trl_0|95GhKM%)7U`6C&#K+jV;C=_q z+l{E|0*|+oGU#DI9ff+Q9oU5hwi}i(bgPzQRI6-3J3-wfDl1t-H;?2aI!m1qNhux^D2MksUA| z&F5mPAqn*sOjKa=eiBOD#3+tKy{C0wU=_SO%b{{r0l5@+%Nmhy?bd`26FIEH7f40l=Z?YOxWul%_^aVW3+Z|13DKLBZ54H0Mrng$EhX7KMvImvbj z5+5!$%@u5+l=pEC6JmgIoSZ8MzS*aW0Ex;A9g0%D%O(n z@^bLh&z@{Pe(2Cz{3BwAGKgmQSX6M=AizRLm5?xR304(BC}3A0jGnX?L6`x;g!L5k z8Y6!U%Em&E`KUT35-NMX8ly34!>X*L;mq{u$snBraxkeBzK2fG&Fvk^H#(ohsPm>~ z(`Y!Ob(~JAfC~Wc!TwPb9UKgyjori5A5XO>TxOx;MK6J7g(4ZmUl167y}U*mvIIz= z$?o*&4BJX%n(ZRtbWR97%yl>iJ;a4Q-3p@LTAjRS2;V4Bt^>TCtkD$&BCz*^nQ+0~ zJvAj7=>|=uH*_3;7jgK66}Bu2fKZ-#9@Nu%`9pzyO525*;W=>Yg8TWR^#_r@*2DUl z$iEA%GR(kwLv#EF-RfMg!zK1meqd=*e!%^|a{00xr<)iK!!_Q(NfA=0<$|u=$Al1O zpLMZmwOA>b2$M|+IIE}>20=B$7{=+`)eks$h$|3M&J=TB?OHvSzXpBNi+BcP*GcLF$U5+x@Qj}MF2|7wgjF!f zSvqvofbRaCSX5XP6{z5Fkr!blxyINS=Ws*{X|I4M2UXrlhEe3Kj81Otx^*WB)8J$2 zf{X_av@|A-Tz1zH!}-1lCdDlLzuPd@C?=2C9X^T!Ob}on?dyC8UFnzInXyQdoTgq+ zA8KzI*mvtX##cr+E%rjbc?dHGtpMgO^n zX8%x%DoVn3K*c*B1t7p;9C`8L_3P8HDVCBd#;GlAZo~-1_2i|EL29ti#+^HFVjGc& z9InF@S?KL{?)99wZLB-7|u9&{iQlHg12fP*( z;z+kKIK05zJO&Vq*YJSncWW+7ErSchie$!5pA+9=e6!15v-_5GOkrpMf|B)7l2q$Q8=ytNkfXY~dR|1p=l?7# zQTTF-2f4X(BRm-Gt^3yci2x?f=YxDA0H*5;mMr;4kvkHoA^;#tu^&Iq2X-bGuml(s z3Qg3K;G=SL`F#UZaIp-s zpvl>ga(%q-ETmiSzX-w4?*deaZ0;JcMdd=wZ-Ocf8wv7kv9Pd^!R0!Y&kl>|?&Xbp z*{@DzW5Bb)$N5z?HO4Hi0-Pg*m4UF00+dW%1q$K1cMIn+a6u@JXpyf0l!AKkV3r3> z^w>cFy9he22b8dILQ#7#0~Hwfzn4Ct z$I=#+lq8RCFEAYeDB0%ZHDFQl^F;%DS;L}zr44K5F0}FRngKudC7NA29jdKVwax-w z27mgmHD?Xf@M8Kpnjq^y;e>mH)(@$Gcgh#r;75-h(O3uVKMv8LeGal)Xh<|{r|G^% zf!22lJrA4f_|W8VK}53TWLaR3tr)?d1803Uj0j+RPwA57g7y#0ZeFsxADD;>KG+*_ z@i|mT5Z$W-y8tT(=ip#7Dx)wf&^6nd1UNYB zH9V!fp#Jwa0?tSA4#&A1G&|_;5r{1_Jfzzv*{h?8z)czZ?)TWUyB6t1Mit<^9w?~5 zUb~6}m3B)t0sNeXd|}KL2&v}W(-LuKpA1wCI&7}*fG)@}on;k+q)YG!k}lLXsJpP5 zunI#%f>2B8bDmw^OW1Uyu7KQ_4$2|e!?)u>)&1=y)0@72eW54-KwutaeWZG%R=sI- zKXI7M-@rgfyhw&NKT8x`ad~+E6)RRunB070TJpQDE=ASLz^O4;8gPJU14*Cvpi%Sg zOp1?it^d<(hT8*@Jnf}PR4|^WVnu^H)KUMo_6Z3IH`*rw6y@jBYV=a)IM#5|0MHR3?lAU% z4l*kaV5^iI?c$^2XRI-xHY&u3+y@;|QLvcNsp8@#>e50U>gPCF*LW$o@Qp=Lbl%+I zLx;*?@`!MQzJXXeti<=ga#)B4OxI~ROq0-*<$(Z$(8PN%Xz`LI$z)0VdvpXn-HB4i z7<-ZUMGoT|>K*Wa%29KV-GLd&N8)+%;06>!@K(F|6 zxCa`QKmb{%3w8sCI-7jBeXMIuxKfW z;<+qdO%&4DSLD|V=?W?E1q$omsY&OzdV#f%rvm?k92}x@u^90H=>!KcM8fD`EIBJ5 z=-XMquZOV0vHhXAV@v6uOx$Jjz1D`R1D3abwAUGSHF#>_oPx!C)v5^%yj+M#xIRvo zRc}g0_o!`k@eby#?d=udP;m$r7_LzG$BLOIB(z*j)*Bucz5V?{)SK0t;--h%om9x< z#I9jcTnS7q(7KZdXB`J$GDD?K1G8cooF$0iv;J6Fb0>gqGRsd5Nd%Px`W>nZP<7$? zL7DPb0@IIp?Bd}OO(iyHSvWqx##Z*R*V_7z=%t-tXGyje=nb)ukBP#5D}w)}jVSY62(% z4wXzolpVmY;j(eae8wtns`i3lLSw2V%L3V1P_PY!_8aIRu0X1eVG#9)=(0k)B?M=x zU4Ux(*jNV!|Iv#;V}cbAVw(d!3TBKiz_f|Ziy`zbIG7v1%!w$3Fy!1j^b%rhPKBLs z;ow!K5w~GnTvS#2df0{`szdK_4Hz(mF2oXygrv_HLF*p?awg76^8h)M1(?y#0wlnf zrP!2EtE>AB+=d;&A21ZU?&#1SPGMMGOI(eiEAwA(f)+F{c^Cy zx0(MM+OxIL~T5{1=eO!9b&~DJI4t-T|i3B-DBU4WbEEBWzfF??(5G zz(Z9%5k;he*jNTP$+ioFOU%v(-}Z(B=iwTPH-*IoC*o#sv$GNEs6-jsv@-m}~`XTtJ6FgXGXS z!&nBvXbe}@3j7Wx12t>LlQC0gUIv%zcB{ci6q9~_?tH_=@JGP_%^4niw0Z4CP$8|| zySMN1Kg$t+sR%&8!pxF)GM2d+t6`$?jB#C_)&QVsc=gGraT1CPXDFcYa4j%Gp#9N$ z2cZJ>QYGpx%#6-0-D3dz@@S$*+&dH*X{M`-t;{R_f{7ErmZ3`PxP<0>BWk+A5<$fX zii1~g-kW8Q;*TR@0@=jSGYh3Uynx`I&zg#$p!f(|19NzGC_iR0=d}Fer5NKZj56AQ z=kOkkw)=~l8OV#1cab3Dz8U)&;@s#+3#`ER=K$0(vH+zqXymn@3PvsmbC#Wy6!LWu zY9CmE1v6u>Lf*!+y>#Wu3OH0raZU}+pF0Cc3yuj5R$Plq!iHkvgeT6Bk410Kim?N2 zmc#FHrVj@Q-qzVUmo@fR{O+L}Zjg6vflQn{jxNUYkR@AuVwe1vznYYOR&fTJHV#}I zrpODT$cDW*BJt0spGGf@_B>dT-++(vn*7W5US(EDN}P9;3zf#`{Ay0lfBeD>4E4}* z2!$GX?cM7FKGVPNl#T=VsM`!RLYC$rU&irpxYARc0!`)E^%sEcMkgB>7a&|4Q?nmw?5<^z`5NEc$-wD^w@{-tV;tHDm8I8x#_lM&f?sX<`od*Vs+z zdcH{ANuFRT-<&^hE*E++9Gi*ahTS@SeSIe^FJAlE|M^bZ+O}v|@J^@Yt)bu4#-|ZD zW_tW=`Pqr!=y87Y4OO1OhY-KVuIw;|6F}A2p+-JAHh=DJ{ujG_YxgY0F-RE0@^f=u z=(n5V8bCR$(TWvZOjnM_Y>XqwYz$C}KR91>s42o3*jhO0kzodG{*aH@^Re#9CLcR) z0j?J9y-X~FGi-Y?WqIDQ7e}gc7K;_CKonv)xi1Fr)cc*X`Q(3rWHM*$meeo9W`{sN z2m_K+ICl!!UXP!_nK!U#7RR;LI{?vV$RCo1%mhG@sS@C~(8Xc23W5T`kYhS=L&-51 z6)hRD;CbEt@lqI8DP<)Jc>umvH}ft(~pGN4PVBRj}V+S z`_Iz#M!cX&2Oy6H0DQnv2>r}QV=9yye{P(yCL#vTM!tqFAA=Uqd&Djdl)+47J5DJY zySKc@M@Iw5N)Xlx5MXT}wbj4{Klhr96Ief8LVHEW1-ZiRgNj_p`-n4~)%4F6;aRiR zD8^iV@ZePGHoOc|EUtP76iI|X(TpcDl0}A;aKC>!m&jinX9mu_X8A#LKG*boCC=mk zc6J%f4*SL2E>eF&pFOr_gZ3W>awM_4RNTAjv`i%_HR<@8O_$g5p7@J*rQQ-fy{RnTsRHb~otgdp5jyi0#vgc< z^W6GV+I9Iy)d_oE?>~P}BXQ69ZjED9K_d;S`1Uwq->#J#A>|HmwF%rz5Z99niofVwi($CYwxrfael!3K0C*%%w0P4-kIYZI<_36%#y50O79IoyKyR8$zQFM79x&LKkGYt9#=%UK5s^Wx zUI#iH2_xaMx%*`V7Nw@d^oPls@YJcF&9|FbTbJ4` z#zjueI?5d+ejDHqM$&*pAgKlb>F-#72DC!l07gfOm+{)SkLCurK6A_u>8#(hx@LUq z7ASfxv^d{7NCrJ04JL6RfP`qyxbgcAfInIzJ?6kb=g(poZfT}|2wh4t-WugE&R>|X ztXz4c562@Kql8Vl#D$9zn9svV)B^-UYJY?5L|7>9Xc~Vg!`O9oVGg1Z3Oo*zDV!%H zV}z>hXMcZxi$As27|~v}!fEQEOwedcN5^_{3X#yfj>n3bgU^@9%eb?6-GXVzCU|J| z#x%FGN-*3NNKa?NgsUq#@53aaPNW$*tpWJDTj=YD8t&|`vJFf{4l_H5 zJ2-p%DK19A6RjzrewWeVUo>z6h*aZyproYa8b+-6KFp3g)g81RiL?b+3xpj13Hw;L4u}B>Nh~5}-`1_3*fD5GB#Ef#)?`JYcyOdKgPrhsAiD z0AeW&iBo9wzuNJdoB8x87l}M<0=wQJM&mOzDxvm&T1DwSQrzsRJ zHPPA;(GyeZD_xv8!DQCP#*79&kh@X<;URJM{)Qt&-Ae_}{_^MW@J`uNPHmteDUbQL$}c6x->*V|1JUHqh>Nl#C2a3tN} zor00BuC4{UzOe-ZcKrM|mu(YD>yu$5$-Oo#B4SxK4K=9Rm=Mi*bou6J%v^zcsDz3G4Rd=(1hlJE+7;-g{NFU_`s8$}o&XD!q}M{ttkW!#R)(`){pFF%Px z`#Gyu0bO#+B8O+gEqQRnSbYB#!U=>-)qhoQ!3pi)Ak9BM_Qh|)`4k?!kFT|7gFt;B zgMrgKJCW5`p*%;&KD$22XL(B_s6-UvFy8>r7F&H4PAGP}=MS74SqS6#4Jc?q8o{Wd z<3aBfVd2Z@9M1Lv;*~z~)c<_7m$&!G1$ksNoLZT4S026~7<;*$pMg@|Z6AQgBjUfm zwYL8F=xX8R)l<4>4(6t?Yk}Fto+G>NS9bspHgj-Dq7N8jI3QS-INsZDeU5kh_|f|8 z$fHMN^YZelciOtUcb2+V9_x0v-ERNk?shRPzl_2XK#6NGGETnpQwU+h{h@=~%orTB zi0_Y|K+n|g9UWIb>qtG3+Tf!TB)ca5G7YfLE?I+QyBD$Z;umi}Od?Qp*i>AA6WAB&0YVL#3lLX9 zOY2ioJDNp+d?s*ui6YS+F(tuq0}z1^+C7vWfi#M${~eK;vE&LRs~#PZULH>7P^3;E zybEcI_@Kb0zzOh#$P%n(kZv&pn(Z477E@>+axI|9lFDq1uJhWW_Ru!;N^8{tGpJk z?tT4x-tPcH#Bj@Psz+)o(i~tcaGJP6V92M{7J-;fJs28xUEt=`i`#+I z9_b|P^BN!a34RS?7Q#RrvnzVh{lMP==>y60@u{Sd#;0oBx^e1*Ls!@g8#AmtcrJix z&^WzXW$(95q#-B><<~NwfzSXvrwZjR>4s2>lr79s7%W(RQc?*MTY|7KZ%qsw%>)=* zdugpY1Wu&!MElr#CM)vTvA05|8W)M$iz)&Pq!g|OSz5zDOVL0KzSN2c3u}GMCs~=( z|LF!QSsK}CT+I*aGF`cH!0_M3-lWz zY0^REQJu$~uoDt6P@cwSlhf_ww#+-YBc#gEdRw2PB4UDApyc?n3%{+vrsTX$|$5p4mubJ30j z*x;PCqbP2X1L3P!9x;T~g&1IvQ@lE|R z;D2rl%PiDWUB9we6DGVNvu+5tbTi$eL>B4cgz?`OaEm>*T4^t_#iSr{((I6h(B&)S z4qSppNq)leI!(0$82+OlnByD670?-b*KfU>=an?Uw0?xMGO#Y9fB^v}&lf0xlQdb@t@7 z?o*~ty#!5HE7<@TG%+jz0Ne8g?6QRr1UESRk*w5tpwp%B_oz~hwLqx5M zjr=|$wj*^+D&8lJCJfQztg=g`+=S63T)SXKh0%yebRC_bLu>&2EnK!}sylgQdMSP6 zuja)55Av6^=OX{XG%a*FQqj zC1Kpv@>4zpL1!aoN?{{P7+#UBXW znFe9SwdHiKE;w72bD}f~wtNgwE=crko3~u(MbhtZ!CB4BUN7<3lfEEuomd5JO06JH)v0-wh7#?GV9EE&o_U6)cNkVePKe@D^#AC##{%! zh_Vr6U(ueCp6+gQC#S1K0^RzAMQP}o~LHiIta-6rP^oB-`6A)+Wj zD?ffzw=?G+uF0G-eR^NWo;hl2@15IifpeH7sM)*FS?Y8aLdy4j(48QHdiS=i$8Q7L zEL?c&IZ8bY_~8|G6geqjFo<}VSX9X=rJjAupI~|b)97{#p3(k-&Uto=SBe0OW#;3P zfr3{VX%gk)Gw1GQ5O9$Wa)jV<1UD9Eq1f7f)W13PZGAJwp6{`?*|DsILYPU6S8RoGMH0*K9_-t;UNgj1+M z-h0f^*3hVNHceOtfh}Anfx)Tml32VkQQSP)xE!QU%Ks^q9RMDU{Uv{bOQ_bAnkIv4 z&IL8lAP7FSx$-0eA$=VfM`-UoS2eoVW_gpd+av{TRGleSN>@5j=YfX_e8cTW{cY{4 zFd8&0Tv$44>hAUVfC@_U*O!=N!{<9)T`OqkV+yx=W13BG++2T!Z3xk@JqbJV*#mB*Ms|nu(%cdwn9FQ1+XEXyxZ*WFSmG&2^A5q`cV0)%TNCv#` zIeP{(L4TOT(b+79%6++cwRnR!K$<8*RZPmmSF+CVcx)ymh};Q3O4k!L+wI0J?VoZDJoJ3UgKi=P!1JC$ITJCieO7WJc)*>6`o&mVzeQ0p7ry)YJEh=z0$uKNx zi?|W4gB&kg53WQI@y1~~VwQVBlS*#Rz*DNAk0)SF;((j7vT_TJ=D{vllPGTRs19cb z*P5|2Rbq!r@`jH9g8g#Gx&o8N2RKVB2WNqXOE3Ypm`kE9bBY!5NILT9LzW*p6QT)K zcrV=q%3bcSui_)$_vI>*!YWn05P1Rz3MHxB_F1tXUx36W zh$hMI-+3}?`a>$=taA%B;(-1$u8RMN>QCXioz?_%A5;BQ2F-f*=Nh{8 zU~V2TuPegSU!sXQsT?d`0bRBcQG`T3?onQsU2k5;1!Q#F+dC>uf-{=7}2G>+} zxCz2hZ&9zoj^TkHf>EI&LPANXtj>JwgB`Ce=65#hB{BP_mBTmu%(1WLJw7yO?-?iJ7&Tc@6njs4|rLGc>Jmlnd~(>ygzMz4CdYB^`AWcu{1kar#K9Dl!@AO-jDD0 zOnS()Lysl$ju%_wC=L_UnN+!F-_=4N<%X8ou;ks=J8|l&q&!2-SFoV{Gj@OaxuY4{ z+&nz9z8{97UZ60q3e_kq&R#p@^6jpKrP|FK8`H#WK9%1^orLy0uAvU}1tM%_-<3!C z@8a^^e1~63yQ|*vy6Uc{R{iUMrsK zXrS+-g2E1~IAS zj$}dqMhqcv+mxhw?HymGLoZO#{b+wdrv2CF_vSRUH#hI_xxe{rsiVs>&8G-e0;b(U z7|@h4iyUv6Ls;7r*&6v0vH->2T1EG5<8RH1Id`sOTAlFkSPTH@M6Jdtym~b@5Rx}+ z_un26k8`#P>!up$>-QXx`xz9(6uMtV%LtRvR-s<|uLsr}9^a>wGy?kMpuRPRvSQ!E zMQ6>b?aYItnbPohqOwS6{=74XtM+A($nlw-2A$%7XfT`UKeNX{@q5XA2dARpIB0eR ziXVWb;wz^l)CRHTFMUyvp$jK11W`NSb;b6t$s4S!zP+`+?N(cLFyoGB4*$oUOA?o= zQe?HXbaDF7)zuXcp`p|qo<6Cq@w&hF7avvMI-op1v$)dSQZW1g{gEfYR+imo3ynfm z|CbDmB_4Mbw`yEq4n|LG-348SkAHe%=Od4X;F6N}FIQB3%RY1-G4WGZ|5BbQEbu@y z_U7u&Il5#qFq*;IE|ooQB4@m6&Ch(O8kOh-jv1aZZ}Fa4y~@C|!rMc}59G&ggpBI7 z#!8h66OYR&LON1CcP2W6C}esn<_zdjNma(_0{4WF#?`^$K2+=!{CPt>6_GK?Kd$i>P3$R-21xv z*x&cy)RM`Xb?#o->GmXGA{TWPkH+39-!lgy?!exSflW%@Q_ze5Y&Q*jWc@o1guBFR zNAT2<3zsTyy_)3x*!x9q(fKor`&Jl~9NBx+Vf!~%E-_xc#I0Tz#-At8* zZGn^Z%AeQV6dcr>cAff#g)`se?j6QDnIM)QWSatege@Hr{KkDW#pjTU0#ALva}~1V?3_` zRpcyEc&s%V0Z(AHbiS+TB(mRit1^j{}oxx>z3sWkHqOnrF_;J@iw_$v6OqOY=Cw z0a=sC%h&|TC)r4_{&EHup|!`s)W~Sj{hOtZjq^^&oLTyP=F(543E~D(Gnh}0T^{(B zitF8*bYNd?F0T8SgyzS&$BTexQzcz?*Ff@k){rL;w{(J60U}ey+!ydGDfgK16zrqK z{ex;|80k+^SjKk8XQ9rr5YG30!QMCYGT(TaJ)jWzIxVH9rUe~wU~jUgq&5?r~<4NP&j}dGGlmG)R~_|T{k!?((ty(0aZCh zc~HB#tKYEsp51L?-tPdd+%r$AR5mVab-%4KzEJug-;D%G`Ys4n5j%%c}KMQ6uQ_Yy1n!Aa;lJc6mu( zZ|@lwTcERK>1}1f3KfwvNF1#plSLRYSKW9aBPX|#df#g);h6S%{AzK@-HKiURxBMs zlFg2saD*gmb>2j!?knoee}6bj{R8 zW{-QsInSDxu*L@>Ej%1Dr6-1w z)f>%P*F(fzPOIrFvPuE>2R9;v1@uQ2n z)4siX=Od{01duiWnB!uVxys}Dgenfi5k(l2kz|EnJOC2q(_!0S-$k`776n!d2%jvj zAuIKIp&kW$9q1hd|K`DL<^i-+wB#lT3NFdX#kE1-SJCy8%so(ku5m9RQxRy6$s@@y zN7P2m<0U?IvSb-f2{IvmF=>r}9->?S z*t10jLw5`tjTN%Hf?Kn!;Q|3LnXvDs=H^GWs^`)t-lKDf;8;{)ux13uM^caJTEO<~B zqXA3BL!+GnkXeb1N$Ti!Ns<&^? z1jGn%U#zMIF`tkRl;|m`O48DgoA$6X$zlUV82t?23SbbVu&0z2gw!_$r~bvWo_! zn1X?|UONoj{xE5vmSx|fqeN(wQ}OUM3`NjuiD?I9o6d>>qb_-TOy=7ewtgf)rCGp! z-8oYE4edA*fitRgXK9*2h*G_8GuO;r*`Rs?y@Lq^1~hVJj7dLrpD*W*Cvqd^R<(PF zz`eRj-Z^GxAn$QbnS2;GqG{1&O&zJw%TT_j=f39|AWkLBrY|)aS!-EmcH_f253_EdM5MzopnZB!5pmMHYmvUKChpKzePs6h3hlcE*8HHCcoF&Bwx{Q0rjE zyqxh~68Hrjqhg-h$#;;==%Xhm&)ds^2VU3^w zSE$`_l+Utr8vEZY=t}{iAMTe~zP;D0-RfXCZ|~A3?f#CMQ#9WgYfF^XrDAu$lMRkY zdVisG;Kz)bPVHId|72eN8Ny7#wV&*y+Kdi%J{BsHm<1D*=#5$~2SBNf>NIHKQc1;x z0a8X&A4F>$7x%zX4Zeo{8XvVqn|N~IYU7LnmfvYpsnC=b0F8hWdtlnKR>Wf&kwF7T zn**;WB{}2=KBBvhTRW$ld%%dskt4|%ldj48JY=5eqcTW(Ee~ zRBAOb(LJ?Wq7kM+Bl8)_MT6##=^s&K$!#P3(e%Eao)(lE>jCD_p&bbG12sS1*VNnu zH=q?GXOnY2pT2o^L*_~>Gz=aqFn7tI5%70{3BVq+rU@XhM*p9|haVFlhUAoK%|lMW zgj|t{A-Uhbzin?Zy*>$jDrqBtloq?C4_Pgf#%)IcERR=lB_>t+$6N?A@nuO#%CQZa zGbbn4grFzjs}Qli-o^I;Rv;F5st6g^FlliCx@5JI73#4McZF!4Fpj^1lRBL-qC<^- z*{*&nv9;hM1XekSc{N!FA*f1&HVzNpl#HB-*$~9Y9|}spH^z_zB~4IL>)Xj|?iyj( z12ATzqZ~2SCrJlDZK&bh%r~O0C*0A^tqz2$TF0S;^?XPQ;QUu&XsPKq;W*g%$V}zA zGVFpFw*UY^n5nDc6S?>0|JD`>&FHa);q9`S92CS@T4uVX@=RbsW*bCqAc7SOc zfXtAl1w@GS4_b4E%pt1BJ7Exf;G19IeTAHeI^Y5w!XcBjrvR8oTLtAAzWxA1M2JL0+W;tmjWv%k$LTCJSKOCkZb^O%;+B2jf=Xz!mLpwz}=QM_6`Ls+4^`*paR1bApH zQB@s!!o#oBQGyy7!=&^e06a<4zI~^liS05-+@8RV5xh6gVP7ZjKH$+ z3_eCcBl#Tl!~Y#c>Aztw{h#=!Acct+SWMCVhYx8`7yeI2TiYduD}%JE4eb^O4lEl7 z=Yl8hD3$ge=JfV{lR-JfCH?=4Pxn93`u=D7TdojmiyV{zAhs`EINiuQmWTd4kf46# zvgM1hOEOvL&S7-rtNs967(afPozp+%8@`<~_J;@_>9On1@2|9!nRU9-XfwSq=ygl1 zSIx<@XRBqM6`DBjrsd%7=H_;`Y4CUPC2&*mCOftny*Z|nvHaw*#hh29?Ra#aD{o>b z!gk%N7Z<@l#*5mUtX>DH*0EQ;S@MEIYs>yr`mKLNr+6QS#aKUbcXT%U>({U6|M7~v zJN7o-Exvt2_EOp3r@i2#_sD)Xd2!ujZk!nI_V99QEL@rx#^+pWl~P?4UqO4of@`Pm za?{_Xl^@V-{~yG?c|4Wv{x*!LMXDt#QJJR{B14%aQf5WUoS`B`R3tM|B2kD8k?N)t z6-r3ToKU0z8A6mfLx%S_mwwOtJkOu+Kd;Z;`@Xkjt#w`3Iemv?=oeW+{xBh9QdE-s za+qt#vff*DBPHjrw$86ukZkbgqCW%c4dz(Lm3m&Yy8D&V5!TJp=U&3|XY)$LiAl|j$=MMj0toNB`b5N_~F_?)-t`C0EX192%E z9LCQe(TQQR-i@2KDQ z)nVKer%`yzSrZeNSPr#~WYGLgCiZ$8wCjl*^+v4Oxs~cG$*CVbzMxZ`T1@)@v1fZ{ zPLN@dG5a~LHuch`z_2mv+FGNtycO<+`c?CM({z*6VpbYgjrYG zqb`cqGmb1yY~T}@m!Eth?pNCrFnr^bf=1)d0eZKD4C+q+q3Qgi24bI>8Q;j*NG9OQ z535!ku5bCas~OyO%Hb)-^%!Wc;2h4gr~l)?gV$lioXl= z3HFL>1H3yb$e-x!*4KQfVH0S$ZwVs}acE=^T z@cG$Kw)QIh{i0lT!)a1SpCLf-(bbDwl%<7La=&wXHk&_lsM&l&=*sqAlgmO^eB0gl zWO5)W$t73w`B>rE?UOR??pF*&Gfo{v1xV-kjaYH9-q{j&)zP7FvX1=wd>N0|E?f)M0mL^m`67<5(OW`KGD4vFf?;ne7`!bywKSth2XX~cfxD{WkDAD8RqZ8$iC-wY*v7!TQ7cKkmpz+`7$TJNR z$Aj_4s`uvynEZIFc+Zn}hEdYSlz(aCz3VJSB?_p?l0gf6{rl``(~hlwVbAkkjeXzW z=&qmJwD@WKpX1)0&0p@WE)d+?o30|BNgD*UjO9AdU#6#b<;Pi4>W73sOH}QCNIsvs zMoVbxOwl)O)jVpl-@6Xs$BClk_nL_U*AA%+>zq@gqG z%qSCW8s$RvG`P5tbGXWpm;{3)>CYcN#0vELXE2VE@$|nZCw#vMUt6xdz>^}UF|}mz zQ_6#b$2JZfQIXU5gb+{Y*j>Tpg=F2U=??GvZveRc*`|fj7%j>|s5I^Kx4m&M9=K3> zQHwnEwL0Dxv&psa3UB?59NBL{)yE@vxT2eOVr?7Pb!#YyjZ7RCoxhc|9pCPdgSK{s zZ~tq7VDT#2sbSZ)?AwsR^6y)_X7cXop@E+SAMFd|7=?Py00#Wh zn(pLnR`RE67E-r{{CQ&4VAw(a@9aS_9WCI2_ZgQ6E=wS9QnMJ|TP>w?JoDe*yX`qH zr&BGooV*sMSSYNsqnrFIotwx-(BsIzSWprcao-~sARrfJ96o81M2a!2OHA<99p(@a+VNj2Rfe=E80%4P+El4;`)YV@_ z%<8Aq-$m9HpBPIxk;C z7pAPWMVUZi^aGV*q^-RyJ#=wkc>em!vVJ?)b%n^e^SeLj*iVE3Q5?ub+NK>76O-hz zIIDDskJ}TM*4%<~4?v%udCfDQO0Xs1C&#R!-DPJBut!h5Cw>;3|AvS8KPsG~eJr$3 zp!y-oNJsf~V4I@eI80o1`;a%a0F+U^-mvVJ?HA(h<+@RxAdWw38a9hk_2DV*|e z(4eER7r(=wtVY`oc&Tf=5=0LOx{SqRw}wa+OO3XK)yC1HHgtEFR=3E+G*ljczl%I} zd$~krM%rC#7DH!&y^O=l@5wOCQJ7E|Llmb$oLgPaA&v~4z-pd9-&scE7SlzC zH@xa67Qg_OM2Th4hMsp6ss#{Hp_Xq4!XjZ4OhyS$dFkTvVa4>1sp;VlTW<(OLy_cj z8klgw^t5MMmIGZts^ir!znYh;`TgZbaDlTaDcfcjUW9>D+; zGvx%`ukUDki~q43XdXZ|EHI4M%+m8ZDYpRO{qI`hRdm-~A#6~h-{9r7!*=mK{YGd~ zQrG~$(jjuu51;?s{O=i=)Ij+Q!^z7Je+qlj3K{>H<9h(=v5R9<`TT>`>(Dku?9idW*Lg?^I=gD!{H8>!z@Qbc>(5_w3!IxA+_-^Z;Z} z(ic(JypIKE>Nm2^j}OQPPTJGz=#;YDK7%Jl%qVS+@X{vhDYtX;HZFT~bQ*{YH^g%O z4cC+pcDq5-^}E1sA*@oO#|=U!BZI%j9_+q8J2Nl8&4gwSu|**oDXg?{9Ik@I*b7X5 z;sMgXjJ8qpIOTtVa+W@ITP+l+fX8lHS3JzLJ``g}4xA2UB>O}+n5_#^$iy#=xXBWU zB77BgYJA{HRJlQ-&P4U6Y;mF`L)Zty7#JplQuxfD{E`Rgh~deRqif{9)KoPrOh&eg zC}$Hh4zG0^|>dBdU%dqA8_Bh?y9OFS@gY2`tvyMS*& zWfUYr;lzZ{6S}S=M_Cp(0!ux;74q{_)YnpEC+_ENp9;mZ4_Mp;vWPI23HV89nS&Aa z@8TXqGaO)wOT5GP!I&S1?KR+|AySJgL^%{0f!OIEDA=?j(G`ci!U?ju6y(5 zAS(U;@4_PY%b`)8NQf^_pF$Z0qep(%uo+b-3?O5`hnrwXf{ zFbcC&#!NkcaFXG>M>d+pi;vC#F9&-tuhau#u>@DIe$d{#|tBu ztv|$-%sOBPWT2;w?pLTrB{ZWDN*bD2`oYi>qR^=oKm$MwOi*5_E~Lj~q17eGTwHwW zlx14W*z^$%STD@9c#hS{kNq27(cmz7XkZbF$q)GwF)X9S30up!D7YJ_riqa>M!gr< z0W44QWcy9c&BY)mM-Agdg^l3oJ>RS``!^^};r+M6G(jCA+?crHaiQWzwAl>FqjOIn zU_mp2F)$EWywOas)Qf?rr!cTRz=Vdp8-#oK{=LSM9u&3~V0Y3IA{Mt0zgv6)OqKhoss4-iU+^LEcxD^lA+$6H(4B7pr2XGC zx%|e%NK+BbT1mKi6KPf`7A{WiQ+&0Kd9ZrXqlPh?S-6GJCS+#jzwt}C3yC1iC|;@z zo(x&IXpb)rd`I4}l6*Noq|k_SJetN%7q-wQN(vZXkyL7;yr*ysu@E5b&WOMzYL7ixU*6W_HHTch}9V?h{*gv@;hcN|*umqKIp}u9%D{@?VkMO* zWZ=$XOQA6`Tw0|UZ>D_JYbp3Fzds+9S%4#ToXmYJ-^GRWI0u^1s5&#!C$)gYP39xf z?53whk|!_%!E`>F=uV^Om4%*R8EwOX72LTl_}vV>ocsv@%=N1B6MVFJ{T6-iEDRa1 zfBmUC*_OV;?K5jlvWQe6-Q$o3^^UT0N}I^2;;@mTJx@68wPj>v^Z{Gij2McU_9Us_ zupuIHp)eFs9P`Z4KWT=+qCjGu7B6k~_8}}PNMn*Pf~5LCrVe#+*PM~E<&8a+ zpfw;cvTtTR0szunM)-y{Lqaj9mT!qQ+(Ki)#{2iU%poX}>@%v9pu6RI6eBK&=JgH} zA>Gz`T__;qF%jAm8Z{a#V*mmpREyESbHVhQVy9hQf3FIor=#w}*-eO9ffSjN_8h{Y zDuG|Lq}Tr8CaAZNkkAierbIm+z;0+fYoyph_=5QS0Q!D+b^~qTPU#SB6qMWoDd`Yr zoI`)L?Bcw2%lG3fuf zeE``P0tLG9M*EyEpBF&H4$=wxA*GquTC0;l4@pEcl90)KetBMgfQ2?sWln;~Fet&L zMHIoH1UK=B=VE=Y31lb;T@q>oI3yp7_p?^j*6s(v9_TFM$h3Iz33-Uph-HW-=O9dC zO0b~$f5t;spUe$(t_UL)@b;v8>#rgrMN|2xjg1=Q3>L3D-WMV-B&TBLXC+#+tHAGK zQ`8#iM8CA6CSlPQ6(c++U}JktOp4Xgr%pB06jalpy7 zX5FBjeH@SymJp52TetR@UzbV6g2(nj^0gu>$pAXG(2_tp|9E&1X;W--Pqr7|+hK|+ zfVQ`h>ikHQlZVKMbEb%d5g%YyQy*B{6NDwpcZ_&;M$dzT>tO zQA0o3pN||7u%)wwBQqWEPr_rp>HH8^I{bHzco}j~80~(@!eZw*xMqllk32bb6Uz7` zamMKkSp*YN4t@@sP~s>P=8c)80vLHSBDC6<4^cY=Uw#)sw4r+}p+CO;1zN!b5rnWj zT*`m_TiSP$dnPt-Y)c1PatPSj?#~2rKtj&j3F#zQfpD+WOGj8poLLSAa?n(4Hp0d$4R_~Ba+pIi}rX9Ek+r(mS*wUhw~*| z?@mCG4@Jj&kSjuvi40`99hV>ov=F4i24!Mx%@aVI>hp&o*|t{FN|$Oon%F)o{F`TU z8}=pug^t6ThDbo(j$euo$KB(q!O-b!;3(xdQY}iydmMVcK13J?6%cCq^cLTlrj(y# z26Ptl8mxmvG7Pblhf9}0-+yskrcy(R;|Ars05Au)dFJ}Gu^gA%>c${kAcq+Q%cT6p zAmvM^wjVW#Mu@s&W{yHtzYlx?I8Wm|`26fdBD$CGbOINj+2Im|{^}r2i^BvZ8DZMk zg=rJwv8Si3dT>>ff$CNWMp094W8Z}8BogCXWGfW=O9{Hdh*UNM&x7{=m6~s^0b=J> z+34wbxyWr1)B$XN0;e|MlWA_k<=?e>qLE>QWrAxJ&ndbM z6x8bS-B=)>3s2ugcRL#JP-nS$$fUPC)BR4KdHf50Ky$jeAJf8 z5;Fe5#GtBojP0!uv{+kaCI+r!gG3&sRe1NREhpw4n%RxX%I6ETuu1z*nj2rbzJ17f z@8OvX<|Z}UcRaFA(@DM_()Y6e1vxwNS~2-?RE%Q`sO1jixIx*K_f0fi>2feM=vyR`<{UbO%GbzRq&nvD8 z34+y@UOm?t*@S_cGj?(kQP%|$iymU8@Jxg^Q+z|27`W@HggynQ(u#CUS>EFK!7BH9 zt2q`NKt(Bs7!gyb7!2Ce0He_Ay-n&50?2=E6|O_NtGdrevC z!4e;*KQ)$lhwhs_5liz($gT>xR&~2$YJCWUi*f|#lvGXj0pq3%d(CGHHWXfwHoxoS zv~!=`@ACtzVn%xuUq@zyZ6Mkw#HNE^_uo#-R?bRU8bm-7#JCXiBvZ$L4dUG}jYrr- zaF4zvDTZo%5qHGW(@KNiMiq%IoXSrUGOJ2fHekNfBKr8Z#E#K*)t&F6HPR-vlr^&b z)M9_MDjsQ+2tS*Q*YAX6ef1`#61y=J*a}9^x^cQ0G`i z3Bty$JXR~iGP0#Z*33G#cE0?A${bQyBMKsp;^u zEh{l`H$RkMS@AE!f>~(oyX~#g&esi}S^R!3o7*c_ zGx#nxaDI}7ziIg?Bi0?Ghhmi$)bDILXZWo4`6|6*k#CI${(EkIBSVSoy4~D8IJ&nU zda?&0C3ao#s)%ejGd~0AOrV4dVni{i2X{+DPz2Wkd0ArwUBYA%866!>db_eH}po$^1a#9w=rX-6^%K@uZZ+KZF780o?=$Pe{v3L=blZ+F8#AN1nGt&j+kH zeMqo2l-0~>%CJK3il}eEF3O0vRO@)yh;uP?qg^lNZ_#1GzGm6#_z|fZYs9UF^6;%U z7249myEd{!-1@Qk^649~{DoO3%`{p)rL#vK&xcNV}=~*b=NZzu%uf z#(PgYzS!WkmF!9#<&S)VE*1!%s=~Lx-2>~q5veqQ^9j7S%i%6d1PQ>ZfPHBtESakv zAO=j5Spq^PVFN`p__0_%OQPVqjSVwLtm$WP39Z&mG$ z#&BD`q)-2acMUyIA0P9{r<9n;;`aCd{`tkB=H{+V>o#+I`1C5y^UOersFe35rQrl9 za+8ihAf@GtEJq_kBShv}oJOePn-j$1kJ|5JKiy#=JK&`Hcm0d2{Eku@Q#x;4W+UD{ zx4LSZTYbY^=7^#?*V>EN1Kl~cTs!|~GdY>B!6&Q}kKx|c_L{2j;7xtHF)#kC#PLvU zk<1M^AzSrs%f8U;W66_e1fS*#h^c%*#Rp`*y_hj*NXobS#PHgc!t{%T+301#$)nOS zkF8qB9W5@*7%VLhaL5_xL!=x-0(k~Gj@Lhot4iKJ_U84E8(Uv$yz3OdelTC_-EFcl z*GMI-;T(ty^nKUFnp=1CK}P1^SnoGo?%i@#_IkXrHT@wtsmwh|?8P)UdaJem<{_Wj zpC7Y&&d4w+S`ejdAhp>vS$6=3`$AKw5C&OC%9(RxdaX^tf#CHi2u(!~8la;QIyedBz6|H2yc zrs_<4`9rfhZ`WdBjmi3Uugcz9ei4cxeao$<7}SFsE=v~Q1G1m08Ih2b^Z~P&csO8g zV8_!a)I`Y((%0|dPS-v5I7SI;N}S`p=8%?NvX9xHBrmqdwqdsM_HIr!$xXawZ`Q>g z%scd~_E5q`F_!7KYsN>5?$vl7DR2~f{2RylT=DAa8#PI#D^E0uNvWjfZCuc#PF+O~ zPYU6h@l!r3%5&pQ5kBRQuzpEx0fD5EmDQ#I3(~28Uad2DDqI^k3X$!1CUfGe&XqGS zd1I8#pG8!9cVyW>Qo7udqnOO6MMr- zl}U+^njT~D7Dyt3xSULwObqg$CpBli^9OgVkT$nu^NJUC4$MC0;J)@*wdLuHtM}$a z%NFhlZOudgC^s_IBz?lI@__G4@LZi zV!|iw3Lx=6(4pQIH$w6?gwPWb$}(LCoH z*~fa={ECFNb6xWO>)B$SS^oS*ccr!9KD)?_tASl}ZiNXKg|?Z6pI)%Izpq5Zsp_M& zVpGAR*Y@Y;3^+!k*cnwoJ0!+xsJ4-U9aNqf*$gJ-d`n2V2^2-BQdjnStge33b`oZMseWKjwZG zCgJ*%gKSycA2@S+pNcxn=f~!D@U`atw2wE}<|ch ziZ9tet4aQ{<^1pS?QfTfygS}m-aNVKg`3^wS*NJoek+~`lVP#=m|u0R_Tph6rHT`% z!`~;fY#$})#-r4elKAOdN&bj8kqI&eGyfy-=MS)WH468Dnu&2~B+>-V?$_?@46}%! z>PKJo)9BJ}yXse<_)}hB+m5W9&q<^y(;@JmfOQuB7fZKvQXh3ow4HE zPq6oD8)fN6+DkN3WJZ54-0%y2x_0U$LNs)?*JHK9hv3bUd_Enbe$wXEyAg36YQeCo z(kP^$--SwU6PEBA3L}M)qwHMA{{-F^oH7DN!ik5Q$64?&_S=2C<-S((`oF*}+nQxY zAiLpax9Gu)*pOA?2yu%USb9d89H7vcGw!&|nR|~c5=OyunSK%2NCguI7)u~m5 zhlj$*fC^_m0dgZ|gTWuJ0<}iSaR2J%ixKvv?E80mYjg&; zvBuQ?c0v5#{ohpJYG>1$8|ET;0tfio3j*8Hj;StnKAv!mtK{Jaq4sFR3A%qYC5lD2 zJzMb7`}2#J;=_wW4PXs%`J1*+F8n=nqP-Y>%kaQgsf5%9wSAHiK}_9H!tnU<|8VF& zfe6K3KGEP2!ESg~yoy^hzOp)5S@OqS2`+0uT0E&0{%xqy z`ZPC_1C@z28&uN`J37yNlip$6^U(YOt+3F!-0iwUHnaCd*`j_wHb#|h5K_#}$PEpg zB8p71+qS7wr)EpKaQnZ$+yzvJnD&N;*S;^LB4J0%#V&)&QC2YfddH62kC!Z%@wM-0 z%^T=)*Q~KOxUn_;(7S66B!`I%+?^}Mym5YVx>s9vrvGvhVOoSi? zq&Gs0DJ-^1H)igsJML4n+G9Qq`TY+6Vd8c?}pW>~kCg9WZ$ z`;bo<%8WEQw=KY0d4eloH(;TD4`L-NV5` zJwy)KDq# zhO&A{aHfHaMk=FHRJo#kuf;e%R7NhOH`Onwj^66$kBXAllnyhR|L)49RoGvC5jDTn z8l1pRd3uhR2j4He@xNEf1AHRI9~Nk!eJudmuK!iyV7#M0g>NeF$ustM}vg3f%n5v{isj0k1I$XW723x`l!}mFPU*-?owVDc@ z-K9-o+*WtKD2O`D7qK!FG{3*F|B?8g0y>DR#DI)(R1Dwl$5NUmxAKNrV)=C)@p{#I?z_eiC&yHG|IN` z*rCIlQi|>1vblU@B_^gru1GYq-P`W_mR#Q^E%tB7sft`aG zTB6+S#((!c%IGvdE?eB&ofX`2R7S^gxFi3|g#H8Q$tlWL6E$6+fXIeZhPLLlKwrHL zUs9`zf8{#W$5j0gX4ib0ci8v8(og;O6q<3$qi1trIHjqn=_&NH5sQ+96YYntVEuqK z;-=twMxoyYj2lrkWM+{04>~iz(t;I)P*ut9rvVY{ADSF1hE>bL)>FTOwO&}oRz>q4 z_7)1@-OMDSEn76gBe=U_$+?^tzjxx0_8ly#2c-z&87S2e{qpA57E5EQGLS5huw081 zJ=xP-n>GnkY774FHbJnv6#zaY48g=FcQ@3o_qY3(mv(W}dHebVk(iIWg~K+t9pT>Y zJ2i1nY%|P*EAHx}H>XSLLHJ7a?VrDRVLs%>j3b+CU%B=i%Fpn|d5j4yiKsSoL zetja`y8Mj*t_p_mwyYCvK$;{H!df;qcfHiz7AG6L<`r?uLPYJnPuZ` z-eqXypv@tHP-?_Btu&)ZyZze94*v~>E2OvRYp9oVw@s<8Ns5TPFNvT7g*M!5xI6=p^@aVd8Vr}nx0dpp`N5iA;?2%#zfVkohFKsZW#Y-SCj zVZVOZwJ?OYY_QcS(tvI1v9ajkXd#v z)zQ$|*WYq`w^u&;#LUFzG+W7ySX%qdW3JFNP@ubV<>dE(UQP@Uu$EwF<@S1x8JuCz z_4ZM1x5JW{=pFG>G_%ohIf|wk;RJ)y@b$;l_;^u_9pS_p0TE)*`@iBK!F}%Z0lc@9 zzD)ad^X%kWQvoTe)U1ckkMH$0g~b4SNh{TNu zMKc8KIx-P)oVra98sohn)u9%h85yV%R^Q9r*ZAp`nZ4fD7@=)(YE;vhxm#S{xRt+r z24&3xzzdUwWi2kIfEuB@6lr&=E0+NXSoN)aXv zno97C>-;(K;+rdqzqD^!&OUnO_+W=Pi}$j&!-tRNQd!FE21^${mWMwua?3V(>^nU6 z$wdwc9juAXL81N##fq-qHxB|1i9p@!bTCn$9|xjyHREmKf=J4u==!hWC~uKY0J9J3 z)#|{%E{7GM1*f&&-M6bsBo2Fr)Ve-9`L>q3^^XkGyWJH>IH3^di9&0A_g zJM96qGV-DFI@!mdZx;M@RBZ&db~lP+d=$;CxM!j+i?am7=DxG5i_JnfMh6%O0FXQR zv6HNmKnd*e5=pV`UiyCqy`*)szr3oYOuv;a`tG+Ut?%H_`%j+~?hGuG)CB7kP~ud; zFed)|Ic{$+n3)rfD!k?SUr&p6lnugnj@%iA!6*maMv}DQ5&^AaeH}L4k_6KO5FU@g zyJtB%9~K`T6bc&*HBUvWR^Kq%n&-SW+UB#~27K46xbz?AV9~Yd*)l#SM@J&ohR7NR zY-DS{8UTF84h}*XHkPG9q(#1FGLf6_3?l+_IgBmn+QySj2A074Z(A{_5Z_Y-6$KM6MjALU&H4#vujmqBJ zf4F`I+5A50v27b{!D(b8ByPrlco`|FR7^os3J{l6j2{KfOCmiO%iBG8du#r#w%_>< zHQCXv3HpNZYhNcW#09qXopUsXy8w>Iwd?(o>KsvbJqCs&?gCqHc=(C8-(2${k+5c+ z$#eczB1-GG;2Wr>%Yr-uumXZqfcsbemyIzwV{=9t$wDkFd=mTKD^9f?O%putc*{PX z!ela;rgY|zQ~vDsalpWucQm8e~knGaQt&g1L?<#*BH zB)v8lIf$MJ3YUZtQxU{$s1GT8$6ZMW2i{aD)MJ0ijXIq`j6jI4lu(g&+qL}jmLE0@ zq2JH_Y$7P7qTk~`U?>ohHzde70f54Dy`>!3W;m9;P85g`77>{kZ!#FOaV`(Bks>Z1 zzrMXN1BV+2e#HG2C(cml?~sf_Uru8EYxSw2#Nc`TTi)|oJM+iljPe8o`HQHV+BpvJ z{6|2Qeo637CGr;I>wtANnjGAk*Q(T|SkT!8J-wJtdDs^D6iNFlI#sB z+hjH9Q$iKzRd3DDEg4Nw*5WNl%F5|@H7_rQN{yTKEt&7Jp5KifJ?cTCSB#GQ*HcSGI5{+QA5@vZ+PyI6sK-#= zH4VnV%RjgkQd7^0Vl=S6e@e@-?!wtMgC1lKF*}lo6TclL-`MQ*Hj5O-7&=X*I6uHp z<}~55Z<~0INaT7#LKX8{A=?#vDqT65*5q_=&9@|LwDqff;Bq&{+u#EjxH{` zST#u&7PA*%={ly1x@U3wxAcZNN$OIG_{pgs_jX!ERj^MaDBjYi!LVPg@=b+Hh1Q2i zZ*+Wp&TphANw8s$Av7S5s8x->6GA?H2eoL7>eupIeGE z!Aq~38ak`6!DwVp)IoWydQ?%_8Hd>bQd9lgTJJGV=5Rvkh*}3}}Flzwz%4@}M+ez_x+uK|oJU?N*Z~%w~ zqq&_xy{5ajxENB{-UPPsttc9a+0)7uj3i2jl< zrS4;*O;6NJ(q8A2CtHx+rq9R%AY5bj_>{EU zt8**)GIcBEACBzG*(~L~H!{gfx>imjd{^%oRiXCM09+=N&w;#^cdd{6=4u9A2Fz#3 znLrJ$SZrYBLJiokLx&FG48A=&1u-Q64>Eg( zc8CU-GL5Y8I5yakm7943<&k~7ZjR?(x1*hP`DT|TCi@59K7)U;8tJq{jDu@K(#(qV znZJK0piM$NyHHVrt74I@;~s2qhyr#|OGCa^O!;tea^g7M^`V$VkQluo6#dGc+Vx)^!XzE|@0k8>cVKZUfc{?`-|t-(&0$PTo%S>eoat@b14 zQ>aK0<1#FNus{M+93h5%4I{IgTFOL1L;z_YKvm|R(mWtUM9CEx!X#acz7-l`S9s=w zNFPnap1LQ38y6w$Ex)^N1a6gP*kZqzUkJoRfa$?zS=j?T4M?i>rzh$DH2sl z>BKtt)WFQoyx-2qHSHWMi4>+2SG;#`&W%QPQcwcv?GBTxxY|(|#a!JWw<` z-6#=Q=V$^`R7BUrG8*-F{plgjO`Do=29p#Gvr}x_w&)JYCYY9{qV|pH`3hiUfaT!N zG;R+bTqyxHu#`(5wH-p} zMu=Y6aYWcSG&I8u)f~0|!!)sHTZY!ByIC85p3Lr;yOWza;=}HB5iA@KLG|I!S&4Gf zBOBt~L?EZAmS7bkLnE#bC=1-j6y5a9Cz=$o0Qp+YcxpY-3qdBgyJwvVLVj3WiqgI@ zvb55z(5YP_Tu-1g(DvGiW*6WFZUm}KzZ;Cvh~8%W7=X>>Ao<-ualq^9KNJEmgz%-+ z@2_9AG-&6!;Z#zgdwQrfdYm5!HGR@mrgTUHzW_Th)Ymn?J&uB7CN3>W6Dwf{c4>5* zw(eUkAmjFNdEK+g=5;r$(o2t~AcL}1PR8edJN0@+Qv7|TiqJF!qnHKN@Oeb<+@x5b zzq>mFYdjrLLTHPd<6vN1*x@_*qMg_;VcKM(|I-JGLB#Vq2PDXC-UD0pc>(|5f-;>@ ztkpiMTcy2$u|~gau2V~m{3*3pBf~Bp+aS0FwYE5RX+3!!@OGYeUJ~bET?!tUOwT|I zX;+{4B1fsvs%+Qf; zZB>@C0+OlwzasOsW;cB1&aWAbs_z>r`T1YgK~;r10^`ogk_CDUaLJ$GADYZ70*m$p z3R8H@j|BQfJ^_~n*x6ocDTfZElb#<-$0-lV>A~%+n4Nliqz`vjo)Ert&XF@W)2#A< z*JZ(7*lfhM%e31(MDh%3K~m8A4v(E^Jm+AZ|A#FT9_jcRa-x7tco^9)Qd>Li#xV%A z>(P7)r9yfLp3vy*SEOuCTesl}D$Rf2ROpm*%~qOStH`hP<^w$U8Og4 z(G*2$!c_=Nu?1)fz)2&dXpuasDm??AHU1YWdD=(ijNo-*=YT*Z;_|9^esXZgwpg%x zCLTiK-;Z7daj*@mT+O0ec`aVj`T0dDULAx-Kxv5K96I*R1N;Jgz`Yqa38PJLsOa2d zGBaVVHL{TMQZXv>r^;Z-LPA4v+QxujH3}bJFyo$^;)!)OCSM+RO??{Ss<@I@;5u7l z=j3)=M6R+P^xaXMN+j~dYmczXEqzQW&t#$=V$)bop=#JYc{ej_8)v=t zX&S-pQ5U(UEBV> zOQW*S#%3RSPrJZfb4vEof)kO7S0r>h=YSmf0NJS*sV{B+f-VOS06vQbQ_czKxk#}81UqWg?4w*rG=1ERO!DWmFRmtFI%lX>;DJvNTZ@I+`URKj zTZ}^Y^YUc+GD{gaG+4+7(09GO*z>$`7nQHtL3Lnk%z%$|CFE6~&;9u_0SQ272p6if zMn8cJ8IgUXH3^|yDRn>vUbj9cv1&CaEPPVaMO??))L8kdThfC#$~p*rl<xIHlvXifAdnEc0CDC( zx7UAG<5OFkME;k$H{b{@fP5Tbkok#BspsDv<>HuSBQIYW-Ki}a9M6F;otEwqsu98? zd=w%~qJ=r0&NH_Md*!NoN1UFEs`2@#0x1JCpCl#B^r@t{&py7V-5GDVHLtSERsEE0 zy7llgU9w`(9#4b9fsS9~>E3t!go@$&CohGmcDo+jjzxocf;~}$DBJ$YLiov)_pSs0 zb5nHrG&?RwM0`LK;y+;AU_e4F$ztX=VE>u9>o+4p#5#?k5gofR3k`Uzm>vCeAy>($ z)t($2m+*Qk$*w8tb5EbO%B?ED=_>(E?<{{)Q855%`;SoUC#RYDmK(SxfYnJ)l4O8b zb%T>fTuz*j?Rj_6fBkf4g^=INb(mA}fh}Dh_6)2Iq|mcFMeVU_pKq-8Fq+K)&H-FA z>qZj;OEsxDeIVYmGP7| z*CO0+pL#1l?l)h*U}S3A+-=>0VFMb83>(DLryRN?S2)mJ`goCf`SPyr01e96sVIy0 z=g!KiGZu!oy;iv}J2iCP$lv%-j0% zx(KWq{t^ml{weXE!B>y<;K_T0CKfR5mO8yM`NsM2+Xg8Dl9Kfz18=BG;L<)s6Mz)> z2^Ys_boUS<5E`p!?n}vBB9PShk^~8ssW@|OiWnJ158-#4t~=km%o{i{D{aX^F9;hV zsCXTK2mz>L12K96sM$`$q|9oT%unQqcxp!V-}d)&Q&k0(s$|3+Re8P;s_(+>v%o|V zxmiNW7rqeOIxz7Q1P5;<))R<)U`^i5u4)C(K9QBfa3#iKn?3quZgH`>9BBXbUeh|L zUiA@j9cFHxedw?d${&HNAPBfQUU9b2f*`?>=-dU|Xza)kF%DG}$}gnTSno{xw8}2d zhQ9m17}@MMT$mVrF5)w@A)BY%z7n{8qV!8Rzoaajp*l|*I)DjbmZFSmF}6+)dHa0D zFK!UwW?eGEkEOqIoE@}HQC-%wds_kubs$|CV9v~315y!B4+Y=sh3S-q2G!Zus^C}m z3oKx2FwC!6zy8=~?j{*BrFCn(reinsa#Q%j;HvFtkA?-R$pq^`7%?!?6q(xrR>1_% z!U)d{9GcD|zVYiw@hr3e5W2UV&e#4&gF4w4rJmYqF$aa7hh%@vMwJVZ5Q|OudTPVf zw!*?OfSw@kejkX11BkP+)JWN9B+4(F)L@Wjo~u`FLK)`b>sQS5vz4`q5yq4e-?DHz zM=4*&{I5rruw2&RV~rV`sOuAIUR9O^TIl*G*lqIe_a}f@+5uJRwY|fZM@23MUORvi0jtdKa+u_Ys zm7!W()6?EA+)>fT9|CGm}Sf@5Dh1!zGvz>X=zC10E)qA8m6WnCT&(UPU70dp$aOTYr=)$}H=w&e9W2FGM+7HppzLOLxTSOnc-v^DPf z>dKJzhtK&bk=Ok%JDc!$9zq~bgI+g+4K<(uI;pRERmw3?cwnRa7SitdU5FA0wkJ} zeBqBdVKh^0q-oEPv5foX>HX<vLHl)WUe{WVYbAW74YW{Q;6uv+s1-8-%+~m!^ERzor zcY4na?&@85NQ&@%)i+`WvAo>3&~u)x;D%2#o0QLBFL{g$)+%*=@$%RYB| z8d!`S!PL}C%9@yVuB)%_4d&}B_8|w^M@S8bB-RN7$^vbkK>EzER{2=lVCvAtl#RB> z)3+vGe>Al`_h4b{1zT(ctpf`ssx#JGST5HaY8pqDu{((?iD|Qi=dDSO7jX9IJg*Yk zrIBv!%3e03&PYri3C)^FU=VvRbh3^iDN z&x%K`oa}S9{(BShFcijAYOy5Q%ryh~D){0>q98y{7ecn*t*J?6kzxi*Foa4uB~ZuBY% z=5V(gYhvfqTwm(BlL*bofk-H*_!3VrWr7)e7_t}N@GwmV+fFR6@T>A2W7#|zR0f_c zNaM+=ob2^uJ@8*_l;LgQy|M7wFt|v_=!Cr299VYR-Ce=9RQqZ|!hP7CSddNE{Oocc zR@#S31w4LuA+zv+Mkyz-gJzI`4|zGi@8XQxz&tcMX;zhatQZaP{Jiu z1z^EMVf_Vt)u~sj_8S{(@Rq&^wB5CyHWl``St#)Js&T7Zq@Q*DVjH=N6{lly3~)1q zquxIMCm&?SeY_Me-Stc%R4G0!W>qadCFkUcAYfsWq)IEGpfK_4q~Bq`F?qjqR4f_P zEA7aL9C>`}D0W=OYS8IO-4l-mWU!5f-s+xgWN*@q3! z9)QPJIOx>#EJfyx^DP-C3XexecL^DY+qFO)4yeI_sTEwbIeLshu zGVu}wJS|p@`hhkjrMAh%O^c?i-h{nK_RT){tsI%-rK+L0IDrJ$9Gq|t)n?=h*Z@mq z+D@ze{;m=@MfWa1&PzB{cjQnn$YQW^(C4E1FUX}p$>PF9mh}NgN8tc}4Ne={H>A}J zG$2fMpGs}4^)RA~u?Jv^AaTa0>;0?DOtakLSRH;%4Fl_ z=H_VGLT0m}k3@3pnDKJ;+4Y&18HVAKz;WUGa_jf)bKlxwb$(UNhUJyCWh_~WyvO1X z8^%AU{^;p(EA!_i<^~sjIa@cil+1eqGQ&<`I3(pFx&#mP>=nP0nOk80fR zf821=)HDkbL50qez)I**jK3VZU=XD=8U`VHW=8sO+M&(c>8ZH=^PipSMb4cr54tDf zJD)l_IW2p0+n3I-+U_x+H2ttaY{JTX?HWl@cqOf|hioV3S}+hzvAikk%1+~9Q8_VB z3A>9-HOOh3YHBj3@$yQMJD}QI{K?}QQr<(g+qIr90I9bYf$@_}0@A!zrsCEIq@Et! zMgB5a>t+E{$oT?;hvLdV&ZXxbYBgL+*@lswneA20A(aWVtofRL1$toXv`HTW*TWHe&c&CaKXwyecQFx4a}3EK*&^dtWMcIL|o$Q$!>OtI3|p1Mmx z|HrFJu6Yl5BErMJ+c6EVgO`{G*#AT~8ZI67+Qw6iw0J)-e$4pthIIzUlqH<$L3Ap* zun~bT2t5HB9m=(54zOv2Rul=L)gEy(KQ_|Hskk3Lwj$H(B^tUG8FVVwU=cmgpw08~ zZ1LDeU){2du*gWq?)5l6KV9+s9qZ&HY9HC+mS$wtQXpoPg>_QoHCC{P-Xexbgy0E& zI1;6tiHbTJde3akRYhsX!|?pctFCvo4p}cx=#p*nXsE5NO`VZi+F^|powgp)D%Ub6W6TR8tpcbb3kE_8de>bi(@}?@yFXFwu@9=!FfU2#1fT7KM%FoIGQj zXHR9lL(bppx20FS>CQGCA6%2G^>*3EZ98Xv>dLIHo?Avgr2&rvRQNU#9|J;Wf!^Ho z?TE=YWa9{+c6lnwwpl(H`F-3x`}?Jv=702eB;^@5i;m@}u9t7{Aia3$1IzsDGcq%O zqR?~O^?AQAk#|E`FgUQJls1Dz<90>u>w39Nw(Y#(&S8_?bqD{8Px^Q%A#ZPUpS{T@ zc5KZZ2Bf1#QfzdrG62E52mLg|Q)^Upar+$`H{~N;Z76RQ;8Gfvyi|Q~_IKs?6)cza zWZ&==XiHSfdW3>ZKa_^{5jffJzrVgX@!2^C-64NN+7-~X4Q%|F9$vgtZ~UXqvIV{9 zrgbkB-3t!cy7kll%@ujKaod4fsNc;yK0avA8H%bpuzPo)FHVHO3Ce6yY=PM!%w~*`C-0l7at>a z50N*5d7SmP=qHaKM;mG|(w13#l7`%S;a;`GhacvR*{TYMT=vA|9b(ftJvTb*$h8si z4`n}^?!*zA^j63qWMy484BSAgXxWU`eD7JgL-K6j-fs(8!{s~7v{wok`M+ET=Z+1a{qz$9uV6JUiO1uxqskTS`Ot=8YK=KJ+ctxI;r*g0|dMj)t9d=8*` zi0oKhN}czU9EtxCVrYJSeSu45L~%vR)UC44OzVw1B9e;xZq|Iq8E>-jJjgQZ=;)gM zCtiZl2yxvev|#`YU&SAMbcJe6su8t^R%%NeEf|^Pa-DryW@oZSx%ZYk=XE1~^K9h% zbx(ZZBhe2)N_WN*sRvN4Ql9DvdX82&FbG=kh=?$RI#>v`RPg%ihJ9SeW`eYC&ht8Z zt3F%(y;j;hduX;Pxi2eD$rU<3y3vq-xd2}>Q=q*_eFO?G z?3Z+C2Nm5|?CWs8E6-dTjt;Cf7hva5J|AM|Zt7gr>wiBIB}v|caQHZg+BkUT5fsA}&a@Nnp{T?l~3q%?s0J_^*9 z4a0sZ@)Sn`hV(S)c&So5DZKkNwX}Ykq|C(rOP3ix*3}0w(>@)KiOxq@MaAlWONwzi zQ}@zgK+^)TR`4jLLjEV#a(b84Kpqd&<3#CsKe_6zD&oQg~p!-o&Q;61jpb+K-gs1sR5MSBWePH6Rhe|15&u8r<)J^ z7g>R}K_FuUCW@9F<*fmXZ8?z8Zm;-%n0phjn)mnbcQw#L$UHZYge?)u)FeYhl39af zNNAu4sgTM%WGFMG4BO0>C<)uVja!CNZ9+n!lv2*?UfKWO^IX@t{@1zAbIy6rx_-ZF z@7-GKyT0GgaDVRmeZTMb{pxd&#UYsxq)Xhd2>O`$hxq=?Q5WEtUcqTQkOHC_Zbsa#(D$*?^Xdae-YQj1n}eOFlZ zsgNA+5Pi$va%7->gmF;#eU#=4$MKa!>+slz53|){r(W)5dqd?QYW~i=qlSPCXt1`} z(9+b>{wm=xN|-m;wc8 zS_;dygy)>K-sqzdu7QY8Ih=Ey*7LuU(Uxq8rXsYJp58d*(O?;g>JphOG{$awPmAb_ z>^ox&FX4V*hHE1H<6Zq1Z*?^~?gY6RHbk2q*UhM?5O*!?dvR&0@Ow$V(Ai`h$RqGv zt(pqUWncqaXgQJp@Bm=ieaJ}4ymo?a((iK3-cI4<(0g@g%4zWi0*SO~lUyti9IJY} z<&tE~oIHgcehFfGbZUjvA_O?w?>aa#+J}cP`t$mAL15LD^`Id>K}<=?5+PX9kgf0^?m>IE)378z`(OGl#$qy4)+og z*HZ+CaV$&c3;iiSjuh#Wl<~<=DB`k5=6_@Y5`uq;CSvCdd zE=p0-Nf{I@U5)rtSN9luNAe4e8a0B7SnGQmd&=HQ@*P9_99%aOdYI5emuYb)@0z!1 zBg$7I#DLru4?1++Sk!3*NLg{TkFy ziVCTzOaLzhCA&5K^h^*vhmJMEtjri3>FOp;h=tex?c28vx9J7Gu8x|)3Pg$wuD~y( zwgg%ukFt?m1!IjUh_!{HXfWq#AlT?ElKu2G`S9iR z9G6wsCvd2!W?)f`jEpuzd}d8C9t);TohrJ2Qh!N%2Hsm%6+@a);56|G6*`>|35F{| zBNG#08oc@}V=!sFBJAa}jXjWF#DgA%zsJ0^+jhIjnd=wOz9Hzrp`-kFR_UiKmpiPi zv`DGiqEU%7SCL%`%y`#JVLgh25IZG;IdFr8IPvPUW|sd;*2Pc)gTtOJTeJ|kK&i+` zfAyK1nIm#J&nZMRal3dBO!bqmQvWs0vAi*YD8xYQLZ_+Dc2Cm8k5&pY$xOPn*&B>7*^m)IeCd)mgt&nvyo8*mx$-|MBU2R+ z)>^+=XE_6&>7BqA#a4`Bab^0L?|7h4PQYf#5ybHz(#lNPqc&Hh2{z&;d;6NRLRG$6 z+BV2C0hH~EDTf5b78fe~`0>qi70MRm)SzHUTN+xa1-`k{f|^0+i{FxxEJPvE=KP3E zpL5cU+hs3P5_X)@-(6OrRqvuZ9A__`Hq)#=wpjVul&L|EQp}JEA17G9txpU@|-3w+|er+*) zk7a-3dsi^U)n6YCed|7fkMv`Mt}FWv!p^F-YumS0*mNcSqz%^-Y4!#-&cD`tTyXo& zoyV{r+MF@#O~0i5!uU6kg|T#UP*54qfWZUYl+l2v&1iTN20|4OA}}1RL|V6o1-b62 z{4fJ1a+5RX>({NTvfW|U0pGt&+eHzR(2OurPZ@zBJ2Hp4{>udrt{a|nPnrvp9Kit( zxaBsC(?K`52)VJhca;W~Lo6C7(jL#dkR_dqAaxvLcS*x^xX6&fW)ITPHzs3vq}BNk zFn}dX8xa{KELg52GyvV`T3)|~? zcH$Q3k__Q3@3UeUe9pb-dapm!7*VXX`FZ69(s=y+{8JH9JpDcUt{49$oGyqX9M~(_ zaGJZY6rx8)WQAam7?)59}o_EOiF#pmwqA%j7p1M!&tY};8=kb6q?bTGe`rtWvxLC_C$-i zVS5|WDIFM5a9MgqCI^5265szDD@`!Mh{rQ(s!X`j78wIslyvEmGnE4i`+XoG;gnor z12uk-EoUOrB`fg8jT;>nT|`K^fZT}kQ0WcMDLKSl99ZSnrp$_1$bADMMS!Jly?WFK zjR3C**GMa#ekW$1cn7dGpw+P?lipmH0tU;{^Y>O{)}OB0bNW{;TGykv>@ZAL;aHAj%ecHLB!nuG1EnXl*^se@+$bicMHF4stGYjoSG?E@~<4hXk z87e|0=fkGj3KNiOh2O_^-lxDRGibY0sn9>un@RvQQJ|@f#bbcTh!z%%_5l_O9Zg~j z1K>eLnID#xRUtNvtPXAk|Dy%?2#ad1`hEY<_~&_Y;1P&fhiTmcM0JRgH5Opn)QfIo zqhxWFX$s*^_-HgE8$(Mgyl=k6BM;JkDr;|C4+KG7dIMq29RK={DMR zCHFq~fGl%z^iqrp{fiEw;TjZO$kXndLX{|`ArE%^l3Czcc z1zPm^TC<;1&9I9ayP zhJ%}=R7mn)exhy8R?;8sk{n*4i1{|mfddDgF%3bx&IFj1)z_)hs2~eHkLr0dxQxqz3yQK5rZ^?J z#a*x_45Gp^jB0RAxzo#@BtC^7MENFu#N0r$?TD>2ma;CCP3WxkuXa5Pdl*lO0w439 zU70)Gfds-Jw&OUZZ)>oNT~}w9~0J@O%0h9uYfZ#TtnYWm7G;5s_tMW zrLK@L&zSCR+#(;t0WxTm~nB`W>HK(_u}t|5BEdKKo01}$N8PRbQz8-FJ^;^ zDQU8}ENwA<0Z|x=gH)3oNl9_-dg;e0aKr$#vkxJX2|&*j%XT#y45lTLDMT3s)n%9M zHY@&_dmd)%UU*EhGQb!9UAt+cRe-2MQ%VmGqyNf0qbBG*XAXz$F8oQO3t1zq)e!fv z`*&&Y-i=}-Sdpk0X(=XqGu~kx=VDd8(RkZrNDKpYlF?iea4B>Z*WjF3$~bn$v;wXquXi1&2^cdY!I1nlBse8Lu#{fxl;YMtdmQoe!vT z?FqS*(Q?I-JMm}~J2OIqH>jn5oG;@f?lWN+c8t01fx0YwJ9Tx_1HXnR2KQ>o@0ZM_ zpYZmc!zcocBxo3oZ-#z9?xc=)SaV`I0ut_mdcU@qOMDZ&UN%N;1NC~dlxmY}XClG8 zYW@13cIz8(I?+c{)H5+exS&rsBt`qsBJ5VK6tNK)iLZc6C-go+j9V*09#NtzN|0o! z6go-?@ChasjnXsg)oU#KTsjp9j7ngSKgI#{<+fj#G>U+XF77Z#3pjze)fKJOi_T*a z>8ZL=zi2nv4@Jl~|HRcHqdBi8l1mfJh(m(1f`jZ*c`d&7vKLLo;i>P~^mg6Kl}@~g?dSo~jGx7WJ468%5!KF}9ec5= z1VVvbff?Q8(Ht`a!o+$CyGP2OL|L`zajxn^Mxy7uHx2|w?^%_PB{|cyX#%8kAcql; z8=oc;q^BnCoAf8KFZ{iKUR8v`a-DRkKm|Z^X=&96YZ^mXv3t}?w~OzI$}Dxf#1aH6 zV#z4}qQLk~{BQ%x5-5QdxzlUS+#hq&Oluw?eL~PMw^lWJh*@!M3Pe9A>q~!PzHv|v z1K!r}R}=;jIPh$1RB-1uOx(b6Lr@t=9S86t%_m&gvN!2^y)GcFO;9?HuLEkIGaVqqIiS{$3yNzN^-b^1ARE68d(iQlS4f3xWVg1S(!-A zY1F7qf@x?eZ6M>pfi@u1s5bd9HeBmQSA*itQI5;MNB6lvrz3|`#uJvCJwWJtNmY}z_7!TT>TJ*QM*_8I8#Yv7`7KSO zzTcIi^qrRzNhl?p6jo}ESwc=G|k6;}+v=)bIgsl%Qn3VkxUq+cen8RCQcg_cb-`&;;H|TdW z?esJ8ayM;)vJ$qC`sl#CTTPa!fXa?U3qQ-&|1`!%yxjSBsM5$th-S;^(W4D{T(1XhS44g-(TurM+DF{R zkUz^Wr)6YjIw;lB=_A9+z-;4yipZ<>6;$_*(T_omLUF7`T0c+@R>4`>n z08B>!CHIs|xh%?BS{uM#hAU-XSs~3_L>Q0O4E)$T1iR7^`#t@^N26u%EB+e3V~_F4YxiXrE?khb4&gsdG-RJcb_-v=0oiF8*Y(i)wh;5^sI9B0 zA5jlWM#E>Y$9z)oyWp(1MTh{|dpRzZ-h_WJyER4bzN`)pytHKbzME7bQFPx2>;hH} zeQ?-}J#fs@ZAMN>hH{1Pm>FtX#MIJSeZ78CJ?Wla07H=$*l+&6>qStl)T$1LGJIG~ z(v>Ajas8csRVF0uvojwVN!1;G4O1*-psE-wVLqOLt!k%E!>!2FxT^{Ezw{MwKF&Le zb14Kn#P=BDiAjD21$9085JWI2)%Si{r)^O;+o<*F^y{I5ilVQB98kxPneT+3lbhC< zyn-OrsxiIYYGzOp9)q=x+9#k3QA}65M04m0Ji?(%wGAtS)x;_cUmk`pWv80EOLvgz z#;>5EmLg(fsS(ObJTOR+BT8#q?ycbU?5VwD1tU$Zg-u< z<8l3g0|(Zw|Mp0egeOHsrsnbB)Z~@QJSp1X(AQjQ|90+qv5%S0}!&aFC@Q|)L^*AC6DUK8@#68c8x~^ zbA73f`Zu)SxpU`{g1UgBwX`f>1@uuV)~JpF(2+*!D|E`NIaz7I_E@i~NK2fb>cBw4 zsO9#eJ~$nZLaC@~*s9g-J_e2a`s`Ajx(>bJ!b|sh>b+L2T=@WzN6ZazgRpdzd!B;j zD6s~LqHQQlOQEUK4+Dc~(p(zWy;rXUktF_ERY^>@@$U3!kLGlRu9=(T$pk&X=dK=s zW(ljeYn1BQ?QI1xEr~7)@xiSrUA2{PkZv-qgQo&EgDF-omF0hXOUY}kbQYM>EFU0w z!Gd$rd%X*y=s1C}zd$JrTLRXe#X%rvP~Qvn)QsNSAx%d?MFL+Nr6}cQSik5@3&^jPd200_+PjC&Yg?NFHM2`{A?fJxDkbeS^dz$V&a5u7+wo9_~j2INu=Yn zBp=9$V4`S>MgDBNpY096lK)!x%?4@R^*{`XlemLYvp`5 z@&jP)Gb`vPq|iiV-wo^m#|e!Xq7XW$KAd|j{x&j-v?OD`Ngx zF-;mZ8em}*h=xT;X=x*g&2k(W^zg}>x?WP*t{*LU5=1Qs-K7X;lnP%OiKi|Jvm1u= z5+wO-SMAoE43R-r23v55;5iWQh+lx$#r#p3(tf9+6npIL=eI#zY-m}u4{&ogx*Xt? z^PE`P3pq=XwIDWRA#Nb*{09rJ)&Nq<86wevKo6?5_pG0%Z6h@bU(*w!=rF^;78C$oHZ~Z!Ho6PM* zG2D?q{@7Z5cf*DZxlgR6R4ru(IT(@L$tT)ovpK2G-23=Sve|Cbr(dL7@aKUlXDGoI zJp%Vd4$DfGhxy8B1R}~%kSE!q+GipS)>==N6n_6;8M(C4l;|00{@2b0K6W)qW!1r&EmJw_c6j-B*S%!veOY}Q{V@lMCd zUS2~kRetpS6$U`zT(xeUk+KoYUegjn5pueJ6D0pa=CO)aR(lSWW>Bg7{?gBiOBC=p zG*{iRNAkgiY!Bsc*fkPwPWa#)O@JbBs0??mpA7i*<9-cJK8Kz@<{tH6LX%Z8QbKmF zSMNQJ_Cx9*4p6F2GDzY>qO9<*y7g#DPu29=>Ie+|(S4vX%S@ND%|VZrDIE49+9dsA z1if3fOr0;QEQ%luDW_N7p%`1`VW*Au47lGfW^9d^^%(_YkPXACQ}1yI3|LGTwuF?B zL99Ks{vnVv>67LMIa3Kh7(5yh;GMf{N~+cS1ecvaj^GykXSbNpv{S3nAr z>bUIM)vI1?C`}J_$qP%~SzXzX0Pz9SE64@-q;rG^;BH5tY_Ij-ak|Rkc^)G&GLd#t z`Z|R3RClh?cL>YhZ(YIs^0>HA&Z<}Ks|RIkMexLm$~ zY?i=MWY$Hj4rh~ROfR;2N#1?{Z1Jhizsav`s7A^g@Lg*KrvUw|#-P8zK@I~=qNeC* z&+VRwMoXdAS!xhRh&Q5x#P?jHXAF;c^+FWU57S{8{4TOxBreIFm;YT70nVdVvE31^ zX=*fVD94rhThdM-TroPb6%M;LXHCP!2pe97m$A*9Ds$^NG^?P=iC4$EY#UY^N(!;(Nwy(otf^3rXOvY753kdamWkZaD=>@h1 zd3c@hTI6JQSuWYGuW(2vmGK@tM|0_h$?eq@WtU=1ymdvmuh~LXqhD(S?Sb6C3ZRZQ z0+c4vsOixVMy?8THmV!9{7pA}AEdyRDXKrkxy{_}KX70m3RU{5*1%~Unt`;?CUlvp z6OSZ_dradx%}h2E+bg3dLz`9cduGay1A@OVEbO4H{!=aA@UcfkyEff0#)OvS%!iT4 z;tRXvfA~|~b306%5wxk`;uWTv5Jkq$r$yqgU*AS7O?bY{wALUk)o0S;Jp%5#a44y+ zXdG@p>il3z%71;K8A&}tjz;130rTg3!)N;UO6O?6C(&lOJ*Tt^`EuBf!j-LQ18OR( zpFbV8n{+mCNXJ~TtKs^{ZCjovmt$;TuvFh+KUfT+r~h8_`ltPGs5<#~yqz#L)mLf@ zg#^(^#+%tB57)kWP>ODL>*Hl2Fx8@zUl%tH-xtAV61y>Zl%1WO7t2f2qwRmLWM$<} zz`~WbnYdEFX~nMzIOe!+$AcYp;OMEo`A|I1Wh=4Y)lasHbTT5N_!Qi=K*8t^MqmKrvDT-43+LDeCu`!^OC2+o^sVU|RwicZp6^b&q zU*sd5PON*8$!EuP=4lD<4L2+3VOv6$<>trvv{Y3s78krg95FigMFUSgoo$pR`WGA~ z?W%_)r!SkG0{Ji!BwOe^#c6L_OF_>YB$`|CtT~<_`U=s9lq9nNP$H@X{1)DQg{*?G zP#AKGLIzY6gYjrZh=ut&@%c_;q*CtR?s^H}YZzUc8R4``=qZDljd6C4gZd!YdDGP^ zCjW?M$w$^})ArZW4a8nZrUS^MGk^~qh46p0Bu#~@@oV55`eQNZjeLkGpF|7vo|gN{ z?jt5LjV?viW2?EYswzaJ1d&#t0BfvNTb1n%_RUP%$oeU2G`~fSuvy4`h?7fspKykg z^R`ZE+@{TN)9CoKXSdv)%E!oJspWX$Bnkc`Ii9E}r3g}@et)NfkiS&Q463nK22*q1 z!EyIvdUAlB#S`r4-0Dyy)t}U7SFhQyg=-)vphqGqeR!G>YHH=R#8sRHkMh@&yff3U z=%?==I>p2O3)0W?f%+tt$5HJgFP1&d$Dhwj4P#b2VAYT zx*|;N>fY{(9Cglp(%MhR_zKsF9DnV+8KA1p%%isHO8|t`)Xh`3ID*ODWVp74*`TVb zs>XNb+i#3T_GrzP5F5M94!L-zjyu805rSjbrfix!eNj zs*S6RS?f9bsVS#{lW~S*6mW?fV;waK&U}DpBz+@|vX}@8fF8cR{Tjiq(_pZ7E~_ch z6rLknD4H8$t4BeHlfp<;Ry+6U^Ss0DeYiu!#jV-KIxN?7+&+S(NR&DX(;tzw#tj?( z<2-GotLxp#-Fe7{$!pZZTAcv=AtenYLP<3Myk)m3;ge=(5PJqdnCQgfWvJ5tE1$EL6Um5lhQ>)2YWW{s z0HE|jf1HHBauACqBenD)nN(&(ycBYj@O?B=>%t+q&qEHMhW)JBd~{7k@JJfH;AWjc zZAr3x1Q{CNUaa9<4y(wi3z{W_3IwF-G&lr06&Gr{`dZ$l3)mO&5E*c}@8+|icmcRS zf-4EXb06W$wzX0SeuT!{<5A&i+^>2yT|m45&qq{B-Vdp*0#?w8*bl9vcULw!e^555<=Nnw+~ciW$RTi3$Rng!puZS})-m_<4oaF!J= zStuTLkLz@-Ct2zPMJhX?xM&0546qo;d;-+0h={0qmre99REx$;oKJ+)AT>pT?C!ig z%Bn_^GjW&|Y{5_}<2b)r-^j z2{Jcey!nC~;c}94mu*XebrejFq!yRJ5zP!5E7GP(Y(Te4IaVWnYm6z{qQrr~(kOUg zyyV5s;w5&2*Z*^G$u8o>%H}0w%?pz%|M=hi*8jT?{=YPm>IMU4gcPYA!&rR^zg=(l zgi80)dR^gN9}zV__s|`&u`|71tZUtSKQb$8hN`QE({Dvi&g8l+x?j!Bv$eG?uRJ&C zNmqLt8=KKOIj`Q4VCVJUJhof7tWSkPPtacCipkgE82 zwxmJh#_>cBJ4%3f4OU-Uvin6qU|{856HYX`R;HXXK^KIym(T8Ixbi*=03KJj`uQP0 z|MT-%qXPnp@6KyS-W0hO#4hHoo^$5KNATd0o}O{?1Jw)%jOFd=rx&{J(yUptD(7O< znl+m*UApvQw!5!y;oVt}*M9XpQQ-0H)U=kC!AVzc10@b8Wt?#GOC!vN?;oB%t)pqQ z$o=yQ^*{RQ~fr`t?Gm&|T;QZ&XtAxJn{W&Y)e7 z_*|=zkr(V7sfXmG?Kjto_*v+)ps^VLg&)o{jQjAlsazk(V#nM1dhp{pSP|ad;xVyQ z1Ux%-?3h|sgxvW~iwC)RP@{+FUmQ4ONEBiDX1J0aofC|4zUJuGE0H1v?oWyra3JAG zj5?{WlYW*tmQ0O=0o<%l$<{0H?oPh7x#RZk(^g3lC=s?e7jOc+ zj4L2m1mqim(#v`&+7qTE95;XnerRsRxk!#ty#6ObW@gD<(aX57+F(G0h(k$rg5X^o zTfzqgmx2@EPmv|8W=OZ>z?$gle)^p8Qa+DIB4;0mtnZU+81k%;7gy5L1>xjQyzazw z)6K|9EzyOuzvQ$DF_b`|!gS?iy?FGqf?1cZ3*(bBt&@J*=^e*8{LS@(@ahDt;6Rnr zg&8>Lr=!eup@Lg9upr#$oUO2!`+A5t!%`JfRasGzx6K`t>28-+k-$UA$f@+Jn*Pn% zqw>!ykyNeB;&j71n0I^5a2P~5m;Eg_{~X=!srOl!yHZB-{K5jTzV}DeLd_m#M;gKt zdBEY;zfaJQ&G+w*l!Sud+W;%HzCMP-d)_@xU*B3rm|Sp=sW)^AXP0SedcA*qXnUW) z!=Enw3=u?(A$NOGnf2(nC&B{TgewF?{&?1Pi0MM^;CIXaS>3gmq+!usbxqrt8FYJ; zPT0HqJzG%kO_-t!0^;PZ0j9yL zrZ0NV|1e%^2-3rASvohvG=S%1;OqdyOCqReM0TUi-3WYsFrIaYZ$bY0HXYkW#oz#`Ioiy9;cMP zJc1`HDZ73L)53}zhYTqjyz27evhUwTc2)|eFoSQSr|C3revsua3>~hg_c--C^cx{* zN~7}ih3mZ72|GzBH__1%rQ7=N&!1#Oq${ zzSzb~=pRJgk=tg?oGAqQijs4bQFK2uhYSlUH7j2{9%yYH_Ny4o`?lW#(^Io%K5FECe zpQ|fLt45DokP#UFdGXK6(t_9-yIX8tI*(vUNC)pyD?YulHRxzyU_)2hhw=8&HSFWKw%Tc7Kb-B>#!WI%+31_Eo0X!31#&%B|t^{+v>&lvKoHTxZ;3wTdk1rNI5` zntQ*q?qTUXY807|K9hYDLCcEKCn}8?RQC0o{#-PkgboD4*=j@fneo3ZD!QyC0vvmS zJC`{dImGOBiW`(qtf%qqE~nb)WOou`7cyuOnI=+GZYZ)s@HPUfb4p z@@>$t;eKkm@?rZ&EN)1QX0)jWVFy3dZZRi?n;L(@158 z?`GIjXn{5&wgNa|^EoG@em{z?NXq1qu3LZpwMS}Q+5Mte0A?|=`G~n}VN_mYmzh#E zHe!AMZ!s@}zupb0Tte~#yePCd8&1;Wk@^?sf83s0RX(fJm0|a%J=XYMQBkljQg^?; zgPQ|_lOHw*Qdm*``0Dv%Cs2o|QM2ZDH^<47bHcPY{BswJ69o#oAxiVl$ z_6V|BP;m~x;yZ|5H{8Jy3n#r=b3zDe(CCK8m|i}VZ3^4ni;OzQ>T!poZ=s6?zBdj8 zCm`GuL=+eF@$=_>COfPD$UNVmY141Z=e4u2csjGd9h_stP74oj>7_2c5E4HvpzZ_< z8d&mv4BrOYywc^^O^S$#`rOW)Iu)a+IDs^r?&n=Y*;Aqd$mZyi z_h%}EQ>s9o`n9v_*DrIXuW&fvE82LvX%+1mA>ZbA4wkATa^YBnM7x5Nl~J`wQ=<#iC)b zJ&#A~g*+|Z5lc>R3F2_ln`Lm1Z>g8ExWGe@Cb3YD>R#fOT$B7RkJPWn*@+(Itaq*U z6&6qkg@o&Vq@qTWANdkE{u4x18o?0bAs-OqluoA9EAn7mx8zR2W98x8NC7112Hh>jCpNgq#ekPV1? z*9+?!c)zo@Nvc7yzM7gEo_o(MzaOuo9gC$;A|Czcr>BhJ86P>GdKgD(`$W98sN4=) zIFEW%)Jt{xBiVD`w|*?A-ZwKn%!y&mQKq?b!h9YV!MY73Jl{xsiJB z*N6Uy8@yuuq*nGkhbUg=FCBsr38a}$%Zc-$NhQ2ZVwN7s&kL}oyV$2kj~?$NH4nRB z_?}jSE@aa?IBTTN`JS79+`jZ_lsM7 z;aPGpk%`cR9tHLu59KcP`k zcROg{LT*5cO|T{jzMnMCXO=F1jIz!#e8j~AmoVOg^@59*9tsR!v7*JI+t75TcG~&k z<9tadOVG6{IcaX*D(8f;Eq()6UBz%MM+;N3&+j;nQ0og4$X<_lu`2iKBc7nFrr~GUa4UA9JZZ z!{nKyQSdx&FJcGW&gIQQ|;%bKxJ55U--+vIXHC6#1+Bdl(rZ1%rvj21QBI~wF zphcEvTFaEb%Dz3wYLz;DkX=BJy*n0;pNkwOp!Bs_1^dsP%Xob7Pn^zqUW(dgxfj7L zWI1Ab_8Tk0dm4@!-Xjfm!ZdzJg9Q1L($5sTOot<3=FC504uh+DV!~X_Nc=LCj zC)D7cXId{gHT{i!CN}BaNxk&aaU>xaHZ%PakLiD%qh8?A*9!~N&wISNdAeO*!P~bp zg3e6Xad*0R-~QJyRoaeU8|5Cw~rg89__V?J2zAm%Hrt z?WcDJW_-A~ayK^dWl?EwjRs11ApPd2+O%8Kt2-D?c~()+c|Of!1G1cBpJi0(7J_3& zBzEjRuT4o0@T`b}>R!JgJs*wmi%)E1tzUey&P<3xj$5K*p-07KIGocy z-RS#G*%gw_z zoZZfNmOtBjZoGw&$9ToSoEB?BPQMwp_P5h0wVYSB*>(EsMgy(a4U`}-%eNzW%) ze9km|)(sx_q3d-+ZN0t#{Jj1bA$;u~R#sNoefD-~ z{V;X@57tTTmT6(`iO3^N`WX4(>g!7x>`$^Px5x&5J4q(bibLJ1ZB-Lz}*TM!x7aX#FdXD-r&mi`uF+UOK~T z=FDzqTnLs`bJug?pGhgWy8~`>iu5i%M;b4n%$zezDm+Xxv>$T`^2SK@B&lCM) zV>|5nG=E-c0BN?`+S;u*SbN!VT%*__2Dnq5A}69ivRPkOEgr<8g4n6;T8E_aVGQ#& z-#r@_7e_T{N0RUDeAj@iqir5Nd6GZ_9JT)IFb5({Vq)kPW)kP7t870LEW&c0r=z`n zw==)ro&Kuhw&>X2pIY~Rd3R^4LF=0-US9S-yXbB!+tYOyFUU&ex!3CUf8Jr;b?|KQ zr0<^^q_-})!e2w(U}r!&mg!N4Tj-TM@N0Gr_R*e&DTSrSI3v%!p|DrI4$s& z&Vq_NX%2lofI>{NEzR=sI)99T9nf6Y?z&gyjzin=9$ zDYP;pw7+rQlVk3r9~x}2x3d|&`ce;2!QnU(MPJqhpPrs@dj;h^|4=sx;|)4^W49$d*YRo%A?xNx6cu`PZz(Aa4ua0^tcze zbbHGhUpEfc{rrAoGA?aTkc2C@n>A_TzoGX7LI7>6yxHE~a}RnrySmPKU+b;tN)twO zs$0~J7^z3U{c(4vKZ0nS*ib>WOm-#TbXZ7?_a2SiqW6am=q`NSV8C+q ztdTA*v%Ss(Bw>+ao__*`G%?n+)z&<1zJ~#qP6b7`PPOPe|96515AQabwr|g)FWEy* z6meH99xutDJ7s+Q)uO_>dX_Hr`xomp(JI>j-#Cln%7|@NL|`w5j}dho{Vq*5>C?Awi|M`Mq<6C;GyHv;QYte{JK%5tk?Fc0bI^^hPIL|k7mw)CRr11enU0nE8 zC9w(orJiTkiFhb}?6*~4qTr?v>zXpP{DS(+dVQ`F3Ky5XTED}4DwU_Gh26=`BWj&i zp7}J%KTZk<2CBPJ4dy5yvUIt5lyx<$r_T1QV@!^S(hI}LO zcDK2QOd$ANKCuu^OOGDYu9b=mlC-3l8I;^nNBO{!V@7IC@>l00DOG%<-TLNL^V8cH zl9|FKNQm73$FtdxhAgzU)gqxF!qX*qRNHGW-?Vwhjw3{_k=qL3vyT|DEAT<;KSR<{&&UcJ~8F&Q6p(kBRzY_mN=pN2`K4J)Wa?k&J-f$&A*nzGV>TYc6euS2~L@S$D)xmc)f1Vo=0nhU4HfUZ6bJ; z7yDgW?CtCo^mtEIaffp+3*qq!pE^PBK3#%F2)|frjX)2H)}I$oG9>9vveBXI#iC{T z$*w4`0459eo%i zRlE9&Z1k@>%25nd9S1i!(IrNZ9)#VbX%aEI$-1AthDSs zH=ar}p?GYL9FskcR#C9vk^)KU z2LkqaL2H$Mc*Bo(#x{_k0m^ZP*97}cl0pzf4!PgX`1|kJkZ5i7eHkwx<_q$Hi=KGY z%)sDs-aMW2qGzrBuCRBz--F^fPnN(OPRKY-)Pla;)0uB0_Uzfi6Ca9H?A9l&6IQTw zv7(WYgWvb5_r*AD_r1I85OPJJAYY^AWS#Vkoc`C&{KrL-ASDY1Ydz}+xcw@rf$Dql zn6wg+RL-M6?ja~btku#gk-Syb{0g{Nzl(Ox$XLpIW+v8O z#X#hBtKZ*RKRlkw_j9RFH7bSjml(KkW4zShprq3HH$@^9PG6EDzQ8M#F+7)*3I++i zedqGqVOVfZ$I5NPp6r5Yy=X%(9c8yL%Zd*`wSlXag zQxO$BqvaDz&{@ksG4?nK$Zb_4SR#MSewJ?hLen;ARjX#s<19O>yZC1&m)Cl`Hey3! zuh$CgV=rI2k$hULYn3z*jF6B2v-wahmt3Mq)iX>9n77~@%=pAR&7SIkUq~Aj=hQ;2 zr8*h`-Ih@G)mpc_Mf2bPygBQ5%9}48c0OD%V6HD!Z3u2O?iUs^i)wdT`Sjh@Z{fqv z-x4A8qkfsZsO0bqpKJu@J-pu=_&$-~l;E4Rw(kAxqwEee*-%8XZIA0viyXCd?diMZ zYR9x#!A#-W*Y`4iO9b1Ag~}l|S`oG<5MM3@pw!L03AJ!XrHY9JQc~VGiq=#r?x9uv zv~o)`gDkp@*GNItW+n-&;BAij;fe168i5jv5p8j5?$=kyprKW7Ll4Krd8UP4kWpu7 z+kI6pvzK&aWddo^;g^0^7G}*ie3Ou1l!CS-N0p{lT;|(cJ7ChP%Iu%6G}5TM<(~sF zF)wf9qlyL&4l^fC(Rurcxgn%dF}OY7nfHL3k z<|-^S5|59_yCg{p_>;f{u*X~_0|?f*HpgyxBG`~f<3⋘Lj~+icr=hU5&=G=F4lyq? zc_{@|$El5D@*PFUS(puB3X_##=T28MB%!3$)3f}r>5y-~73=|o*`$>tS$!$#0Mw=$ z-p6?ye!bw1K0etHs>Q)Tp#bOqF-gn*(`&DTjnB#SAk|POJ=!M(Ac&lb6L{S( z;sMwT9Dr5o%Q{jlB>f+Su;AwQ$!RSG)Ry2souQzSGq$oY56+$0Bd0S=KOr(Xn6|Z7pGLX8Aw@49)y!hYe@yiVF|k71%PQ|L1v_;1tP?`XO`_MoGGg3 zN+g08e+Uje(={bB8(iRHJQbSA2+0@G8!_$+(1>QHUKIJ+n z<}Un@x*#wR4@5MGutY-J02EC*wHu1R@9t*iRryEX{)zn1u7~<3QCsA;_$~wM9PLbZ zmdpdby~$gO-a@O1-{6Ak_J8Q<=y>mL!K1Z5wda>!z*FjEWb|il9?6M-*EcrWWPQuY z$=UI7d8>@{Rw*5+)Mi>t558#DxN&i_7jH-S9!A|H#IIj3bMuO;8nw(m-o{5Jne-sX zP)GgKEJ_fi_-fxYn%AWG7|&CDnn9wb{H||^r`I!VM(F*BBrSz@zl2>95C3-*rT>P# z^#8?MVO{I&RVuEZ`Qr~s)J1Il`2PKVg<6u-s^%7qUc9((4U`M6`r<0hU!{uegX=>% z<&pmX#i#q9Xnp@P{VlbTa*{EX0TA1JcWG)LxLHH~y=-Tn)$tQ=RX@^*F1{*8SDN`} z*uuPm$(_qvX@mc6Q2j5F8V1$RomTpIqG6kDkL@SO2gB~Y+Z>R&X~&KiMl-wSsjg<} z>FeX;vm>wk=Z*bvQ@O~DsrC=oS|<(Iw6?qI6US#<*sXS{PB>;ed+4ow@Q?XWL7vOK zF!OAkp$~iAQqkHjzP$UPw9@*<0u_rfr}9))Tb(y=-t68Q5Ou2hGJ)?FeXH=$zxb)i zEiJjm#V7T3zsB-$6q@ z7#m+|+*STq)Uwd^-Xg0u%HtJ-?LTg&$c8Up{8rGyv9h+@Y2YTe#7y~P+N+e1{;x{9 z>bR9UZmKtOzWgocWIdOA^Q~^(^AQh$jFNVAfWyP_w^X;#Z|K?h3+Nbh&HhwB_Wopjvlub33L z!)d1cS>cnXcYH?Do@xG*5BxODUvjId{4w)MMfpmbsoGlU=ow##zuvym>cJ8UZg^*9 z<)X2Re=M3`ux(H4X~pvibfW$HFN|>dB=4FYd|sSozI;*}*Zbsdb!$5t&S~U4O5RDE zeCWx7xRp&?On5q_c---yIj&Q_ERr{xYiku}^;Jv07Tq2>fq>&GgY-;MXK;E5v!@&MH?NFv)n388w zCp^1OM6}`2=rdy<2FL#JQ4RIQnBk+=rS5oO(AnI)^i1c_J9$fsw)$DvK73!G<{ulc z^By9!B5ZxZ<}>3)ZH;du3$Whf`t`l^FSc(TVZXg|N1IVUN`4w>6e#HVhpYtwE+tD#f8N_=x!q~o-xqpx+B)^Nx6h55 z+P&I`sa>D^^tX;y4J|x0G)>z+d%bPvY=h9LrO)2>t9a4>=GGad_9N7n8lKn?*-}~a z{LNmUPUUr)@W-^mJ z$liPF=FT18{Pz8D*+*gTdbQ0DkAJ22y|naa;ayUcak&G|@2s`le$!JLUJ%+Ao~+@D)Gv(aA}<15F;o%C+&6daIU(Y5S1Q z`F(kBSAz-i-dw{<>xbjoPq1*8E1Mqpv8ihK!}?rzgq@vS_tenx-SLAB+xxAP_a{$W zYhS)HUJpd7EPbqef4cpmK@S`LrP`x+4xTeS3Om%I|Em=z4jr1g?&XW`2{B*giwX~a zyN6x)*}f)up~3d+!x*XLF{AoUQ(4jU!{bL)d|x;Jfr)oGU%YvLaY2nx{hRuW<(pB; zeP8>39L#r{xqLB6(%Id0`A>uVVN+Ghu0j6KA<1uThvi;#Xi=$KeYLjFxBa!?T%EZ# z?ZV%_jkD~Wpqd2h_&WBCQchX_mm> zDKE9M3LWd@c6qHb_1y}Wf0{u9WSq%q_I-{yhME|texR3T`@H$kfK%KRzWcT1qt-5_ zy9&efHe1uML;mx}_>T62-~$gEb;(dGR=#BIQZ)3Isl9i?uh07r@$O}Rt9>1LFRJf( zBm3U3`@lYenh##ZybKSv_U&Pyi|`D*?dW^qlax{<4gT1Us*&6W4UlA^uZ zs-85;k&;hd)QHPJj8zAq=(zBb3Ts~fyWbkA@(QHdP+k;l@)9`$UjO&r3SYf~2a9q* z?(Ua!kBAiIj@5!Qq(1nc;Y>OzI{y@fHrkg{KO#RBH5IW9Z!a%tj|V*h7IN@2t4D>U zqUZqtBpp3O<`^`}SVyU2p|ECBJ)Uo9~kV}gZm`Q{=h8>!ymPgK4VHyf+m!_HZG+~wt0~-=M-KejW zi%^KVLZ>eQs{}~bOOh|w*~qAZwvj29>7m2?NQM3#2Rrd$Ccx5iFtQxg_1&LWraq(q zu=r{t$AgrTS@RLuzd7BJ%68*oAgaY z4+vex)UUe=1;w&fZDH$TQq&{o&h2jFlE5f%u6QK*OCONrJx~jHVv2o>t%lXm*7-Gr#j`6Cg*Z+cQ z0U|0oS9`#)h}EUZsMIOftlmD_EdS`+d2ORwj6~6}!|otk7F@WRYE09QqYJ1reZz~7 zPc-WH+lv+yCC0MplzK=0zU4K>!e_jLQ5Fj7(pABPwj%nfADsLKi01~?vUV|&*AR{+ zJ5yObop*lIjnoMNY$9!P6a=HzuRreu8M8(GYsYZm082CFSclBNRJJ8-=2nsi$c8P8 z(jVsV3wwK1e<$CGB&D(e^ecOji$0e8zSFNUa=wl7 z7t^WVmi`n|B^6Tq_wkT1sK-{%P1<9mfSEPT1~mj>0i)*P4XPhJDVQHK!9vO16Ey$2 zdzU{W58RBWRG^XFW`B#;k}Wq#5O8Pkq&5_45y^nml`mz5N5}!i`wYujwia#@c-t+hPFKEmBn~dfXIr zYO06X4#D~c_eog&X9Aiz(iTNDQnXd`SacJKu?sAJ=>d|jr83ldGtRw0IctPYw>v0O z!N-2oEVZaciwNdW4xF6+1pA^J+~5^b$kH!Oy2*+}5kG~c=7PSU+!RqKfc~UcFSOkV z`!J2mqRfE8%fFqwbd-!3BPU1K=fivVTC*`V8$<$UOEV9Vb#!P^Q|?Azm;S?a^Lhw1 zcs~>U@AZm|)rU|xxlhm{3imcvNZEQ&_Y(@)1*SHE4uq1m--<3alWv$5oP8{1ypA%!nz&!UXN?8)CA zbOME90yUSe-Wn5g(056}q~tf-XR$LlLBqVRzSB1;NVqlip;$5!OXKQAF0cNPy*h1Q zQt2c8A4RLIdRF%@MT8OAL7T}#r%szTllM3Vf6aK?EC8r!-9Mj2$h5; zTR$8qGgR6l3}RqClQ>XqsZj5m|qUplJAYO>|U$LX^|?GCVQ zSSpA1?hUJc{-nn{yc1p;OeCdQKz9BCl=ffCWc9TGC%e8RYrE3bTclZ0EUaGKeg=1@ zpQhEzaGj`H<6Qh#s1{^G!ms(;lZZqRD@tF-jFFLzOM1L|;&V}GH8|UL=;-T7R zMV1Mx+qz9fp_5j|M1zg0|E$k0|9lN1Y-jiHt5VCZb-gvaS0knTl70v$D6Hm2n*aQ@ zWt`g~Y3oipvwERKIbw^}Y|{5(F#__h?K)7k^FGVOEx@FxDl%q2>t6jZSLot(kJ*(wNxXilZ8RVb5W`%DW{*FK>p+j4Hnz&xI0K+ zwR+#-7A5VgVd8|O`mahIoocIDZtB`NsUOr-Ir`Xu9;!8E9BzHlzt67nKh0D3NweDs z4;)|5-|TR&2Xb;zHq{|YnL(oibYN?!FRfqIr1lD=Opn5#P+z4J;qi{Hu^`$TRrwN# z>f!3D(Q$F`U+u8e+8SZ3=Oh_L*Bn6Iv2q5!Bd1q91WzDtp4E=g*12*Jj=3}gcy=!& zfdren+LSO6J!xB0Vg37eIT|4LEsN4Y`Dzh1RoEH`j0`Jpfde4PW!yK?46&)r2Zda6 zr(5V|s_}je*8~Jbb_aj4k9GKM%X&?2N7d_{CPEI+?m3`<%rHsW6NwtzdeM-;q}1X| zMP;~}UB`JoKA-AGsVQ`Zadt~#)-t8prR?KULv@LM(OnmgE_#G|i@1cLh?$CdJj8A^ zo^AJdAbcTxexSZ5{%Eb5I6r&QMgekLri??Jv6B2!3iMCQkC%>+kCprm`tLZQ^aZj| zGZPX&#WNYCIp~|!RTHBm1KSUnq3)Uun-dQwC=H^k+e&o^8`m`8m@w}tv0|;F?8}lKm5_o_J&eYdxdSME?x2_Y%$x*hR1wJ zymry8>rzF7h)c^9VKMX|8m#m<<(r*)u=iM&0BLV0tE$iIX9RS395fbB82^A(ty5FS zLtOr=a=MT(j&88WRJp>Ij-ny$_uOkX=6ZkRoLFNu)YWjC{XaUGLDRthB0fdeA<8;T zdD-0(^n)V_6?%gxQwwBDkdcl1@^m>ZU62|R&Oc0jWrummzWs(9iBbgKtAp&R25PKN2`SnBk%&lx;OxDNjOYYQmwA0b2QN5Cr@}?&(cD$)I!yooM zwSL3E)PRJXCkN>ySb=bC&`L&HNaQQP*dcnT zG?GCS^&SMB3{!dNzf$>`2m}b^=y$XI11S6<@&eQ4G!P`TXC;x8gB}px*ngtY@SjiG zJ2()S4i+C4tmj<6d09;!u~|C(?S%$J8=+*2yxN4JzQ|hQ6sA8&yBYxLKW=w<3oU$b z7atmFSs)szP$O_-ORu~|DU6bQCarL0D-yBm*Dcrq7_cMx8jeUN3--mwWBgB+VQFd@ zm3}N+)G>7&ihO7~K7?Eml1x+}E3Mc!gFp*GDg-D4b8~K=#ic%f43cf@#mqEmmLsvP zvx0xPx3nNO0Vre#YZ@W}c`s@iz8rUts|G`-qmH$R^?0Q)g~twhz8*vv2OSVv>GU?w znfioZWCe5-@aSxSL^2Gq3HJ~;p*o4eI1|+h)%serrXVtvEx_|&{C}hB zhog_kB}HaB3J*KEErL3L?T_yiC%$=+O*dDsI0xi@0M(j(8@SEj>ODk4PhFCu3d2Fl zy^#98&p^QPE-n|4g(`PWiDoKg0RH2ceGCDfLE;?-%91cTB6{noItl+?t1AW>de|no z)~y-&_ke<0Te=S$ zbs<+naqtm)%LQx)dODILv`EEvZL>RES$t+|?sRPCi9;3Q$4+Q%zm;b9KyzaA^vt9P zYZT8`RY(x5HNDt#f?^7yM7ku zuG%{lJ@d^AH!NRO#DBl zwM*4PsuVvR%n96&@CE3d0M-W{G5FiswEE3#OfW1lz!ws6ai|WiIKjAZo^+0|O@hxZ zd2UQSz40)f(e`sHdA=={{vOBUOiTZ8G)4B!~WJu>A3m2sH~vAVBRCI)gx zR&CNhJIiFre@{|IW>jfL-0sX7+k*=m#i7TGGYG{u$P8*LQ-7J&*%;t#r1$X#Qcaad zDScgW(a}N=+leaEEaOLpFGP}DqSGtg*kPE%#W00OY9 zQ?Mx^f*k1jC27(@QS;x72xJi(aPDBs5y2R> zB4ys-eFg9+RUFGq7ZJ$Z+>EOs+2pKPJU(e|80%<-}_?@U+`4_M5isBLZmWbS))y}lz=uXih>XxzVe?xAA}+j2SFsjHb?wg5IeyhVLaK)U`tHB<3x)yJA0(S3>~HD5GWnAy zmDwv@HSi(QcYczQuYToOJ*HhF#*up#lpkz!(|uK)w?^w!$b0?%$9YD#@9!Z|w~M12 zNB4H)7yFS?BI<%yMP$QQ@X?dW1X{QtMih{KaF+xGMQ|;Um(@qoB}f*L-pP@;_p9^o zhYdDg>d(@=ef{+am}>J<_k(Srr^7E zr9se6m z;OcK)J$JPZUIC`@ifjVlEV!bnzw@5LJ|c|?Fm)=HFh5gidJYHg>_@HsQllHLb7qX1 zmAB;$1DvK?A4aFIAh84?{K9Xp1Hz_)_RitfnOkH%17bVfETg)FP0}O%TaP%8F2Qc| z`t$8el>4;JYtDUsgGoGwmP|XEBD!KOR}Maz`wt87`qOO>ou`j)_13y__FA5+GI}xghD$@; zeH~l-E}a~=tw++~Wg&{=2tY&v688<10C0~mSRs){Jl*JXnf}ceLH{fCQVdPO#yYa} z%@y{3cRl_66VCJF$qc1ol9_<1p4Ja6{Rg21p ztcm8G>-w-Ah?P0hP*miNe8-L3GzI6^#XXydYkWjRdW8BwV84`Kg8R7yv!u@gULy7f zDynaP3bNFS`}#PjbMT4s*r-P~wa`Ecw}0r*ukRq^0v{=B3^RzT}jXF?Qc{*bZotKG+XV% zJrbC!#G}`-_22RJ{7}!7SrhZ*e#+lS_jjGnUD6fST0D_eef~J9j9f|XwRCReZc}ZH zu}Af0IZZ&{-7l}T9dRrpdLXS$(CO6@bpn( z%c4(Cm3+0ZbYlYp*6l&Y##g=nSIm2DU3>a=(_N9JbBw_W;YYjnj6aGchx*gVclNgq zEvz%DuS~I)F`m_UzaATFRLZk!P5SoIt56L2xzc=!UfHkix>&(OAp2>m!O?MXpRtOG zhXd9IBA!aFDq3EUzWxYzx~|dZ5qq$wwz7Uy9aPhb_b{A@yU6_9GSD*0+R3&mzMjYM z-G<1cS;nubjib3l7^mN_8ym@gSmk~^$42D&9~|d%1#2sBSH%^rK3y*&u8^3;wV+Cy z3PTM~8sVx@QyvQPb7S?v9;MH)e@SlviKL#H*(M(oGO2)Gtvz@u>|9&|B>c{#j5llC zIRAzxLf+_AaJhS1n&qp?n-b*pm6o;fXrKSmyS+_2%TyV+=lPa{E$Zp-H4nvvh`G3up@QJRONsg&6J;xl=4` z&eaN&qW)Fg`rs{)LIim^SuiPh$rCTCF1Tk8>{=yZWXgOoO3>an{nQEP^{*;T&s|-6 zAR}BVcYi=r3KBr+;i-Cw(@y1wJ>TdbD@-oUQ;d*$;O4$*x37+?V`D}a$DaMPDQ{qR zN#zs~G-;IsiU0mK<(50cq+UY`4MIBF;tD<{^yrcRpM_rB!|XeEJCHwIoDVm<;rd26 z%l>xyscvSkd_nb0hpfll+l*35^ImtAn{Pg76>>k!w{y-ZH~Ol;4#S{x3nq^a77E!` ze395)pYyE5+HFpUbtII9K>@TwVyuR48)?`<<(Yw5XHwd;khGgXQG_aWd7sPL%6Bbi zux2wd?pU&+66PbX#Z*{aWUwx~i{s}_{#4}vsRQ$8*#oMd8fDtn99EegcW!K%Zqa_c zqK|Q@VC|U!<}{AaY?-|;g-^_9M`pJ1Hf8>@jxy5Z)-HIvS1!B%4tX)C<^Y&Q;VYq_ z@D$QDM|h>TUO$M6@d)PkXi%c^@B28fLeDi@^ zph+-IJ3P!wrBl5n%qwU2FB$$F+s+#qT{nuy027kB;^co?{)d&oRuzw=$eT~*rl53k8Sd85tXj&yv{ff=q z_5TiGUFG(-n{NFZ!irz?lv*E*Oq)5603VO{QF${;DCmp?f0K3V`5V8ze0YXbOC?!cm2eqnZ$!6%e>k)v(Mk8uskBej)cDzJ0LzQuJ27AA-(V~243lVM*=fApZY zN@HLLQ$+P22ju@gw~_DMwqF?C&0T|2wS zICNh?gyI0Nu;1|JE_hbFy|Zp?b!EJ~SWl`byG`1*ilwBiPMbNB`}jy@Oiy@4kN(+? zbd>^;7+-6NDkGN%`s)=QccuKbK9~_^X%%|^tBUaChTs8(p2khcQ)m5TxF z3YfQqp^1M&I(Fms{Br%HMn)C;$uE~Twmupz$*77s!h3!9Zb!51ieHgZPc%OiAIY`< zqpQ;NGBbr0or!gvipjcd9p`^Y?9%UkYV>5WvCy&7>DGz#74BE1^837)85FueNHIJw zJ=lMiC^AXy*r80Dnl0?a?f?Fs3aAb-?F|a5{+LTc!H$uO)qNUkan5YXu3h(@FIh0; zZQa$B)!*r?T4k+sdwa6+hnpuz4HM$KFLQIxent`57BPQ?i?Qd9slB`z^T*&9|m_2WfVRJ^}mu(u;r&bkd?7dLBC-; zDWE)%+AbF%>`7LY>8h?6ct&ScyExbdo(3II*E-ow=P_gZx z)zg7oEo2VqrMtWYZHI3So5mdfIux+5!`1!(GYbJ$fcU_o%0|TMNa{^B$qWx?CKWi1 z3T|p}U2!cWIFrCdBb`xknsolb5)szV|&JU#pr=RAOgh+3=BOTWsAx<*d7u~*)c$BjwmFADk+qp9Ijklg^=)C_hUxZ_xZ!A zW>W#Pd)287J8CZFU!e{02CohP&F?Sle?Nt~$sx|P z3hPg#3<9|E6na_E?&)CAUIMffIBy2|CFQ-NeUDP(^~K9Kgh!bXKXI_Bh@d;p2l{F1 z)siHTut~eyhf)=Yj>sjSIs=mZ2h<3BPq))(-o`tFOeV1+Vo>efb7)o&6DiPO4dUNSo{x*Z_C1tsz$uTJ&E=tl`uh5p(9cFLN(xSlA3FWC zeb#L~0r%Lj?N=Cr1ll)v~bt>>oe1*JhCw z;e5y31$=n6EEQ6h${*(5ysvDDTgK}@ayXRR zb4YqljXxCG0`uUqRBg=WG)X@QKZ&`0-s{&!gH9`OWD~V>RzT?ML;V>bj)g;|O^s-95MnlK!();&Cn?|FuWv1SH|Fgxmt3Nd4E)$e_ zT@Zjg|0vo%KT6C$iRz)1l?r-Momc+yZG%$Qi4(J2D@k;;$Ckp+!3u|H;d*%$V)C+c z`B;m4F$OspbBH398n#R-x}UG!dh<-1H)rlDiEY{{%B37FQ;O^2f{K)K;EPwWO#ZqS5*>Vo#((3P?vj-%B0^OM@Ewdl=a$ z$?oBt5aZH&ox@C+T7b|!5jnR9{afe)qb-kFGmI{j zkpKP-lr<9oFANrzH#!^v)CjY!ZJ5Hw$H(XV2*-$`2^FxynGo?yIL0@=RCD>!I^{uB zim+%fRDxez$FK3%KOE8gUHqk$EF(AU2HLhVx-V}zcI;#(jj`BjplIPsY0wirr*wno zo`4RQ`F(5kEGTb9Bh@>rwssB3G(ng7B zF#DihtqlC@N>~A!u$gl+GMflSXaEBN z0CEQ(BFP3(w7{M(5fhQTs68=oQ9?8Q``c>j^n0oNcCYh#WyWZ{MOq$$vtkc=-TvZIj^ma4H0WY zW{m?jq^VB{06zT_Cj{`?7?)ikBl2~Vu^hbT8R+S7@E-(F0~xp>q|r4C%_1r`3N%wSnd}k3MA{;@UkYKmQm3MsQ1_wrEJ1V%ke8H=odnHGG}#Z^+u2XDDSL0r zpX?J=>ETV$+MA=+m&7jI@oo9(W}^>x0UVF(H+sd@*r4xv3Jgcw1wwC7(CPO-9J3*j zux^7v9$ym?rS)3y^i|SiM4bUx0YNIj{VV%BS476>oSsU&03#!>=)sS>r&>-XZN6l4 z*E)*2)L=4c&v|3p>{&^>kZk0}IJ22uHSwaMJ3zWU1QReH?SvDRs9lnk4^@s1I~M-Z zR7^O@tj$3hq9>aL3j>L%2y!;`hh*DvR}y}{F|xT@EN?i_r{j;{_tz8`$X9QQhy6^ z;_~tP$7@4yxN+bIKWemP3xNI(sVKCiMK_ixPYuTU&1>IvpHGv^9=)TN#lM*^pSG!$ z^)UBi0;=?igLf*Cw;0<1tgGJS!1k=BJ)OIAIy#}}S8gK_xSM1n5jqMRBi<3pDG+4@Z-|IP)4x7AYoi0yTnICa? zcS)xc6%*@iy26~8l@&pw-I?_)obNWD--n1E`Xu&ZgoaG>*(E}3tSXvMDhy!lo||#f zWiace3WM+U9uC>W#0$cB8`$5!B&3=4;_RBi3^Ie59f{uAdM{MwQ-kgMG}0KO?>HjP z_8EpU=Lna5$9Ntxkz3Kx6)WBgSgzt#=*&nlC#QQ;wkg@8P0iN6E2TZ#x*xLh<^#KN z@BHc53TxtD`8214QA7X2g$t@r*BpD}?pk`M;iwE8(#Qma!6&D&sYwJJ1QaGwZt?&* zIyh)z*Tk8a%wC42>!>FBo&~KxlI!NgXv;*SCZ~EH%9(|hv5ZIWzN@_m!+yKQGZ8Ko zYM(>gG4b`d#6?GnVBJ6?ZtuRo&sjZ-x0;vE!)A>zuafdrTOVz*!;ea za@(F|Q=<>ZMxk|h)MA6rSILckS8PP+r!Gmb%RKX1#is(t^-(si+08(p5qKoQj}j<> z3Ke{tgtiTZQ~oGXIao6M^;EDD_i()fv`;$v1;U%6q5WzE{Ak0oW^}7PUi;>hZp}q111F+I{k-?`o!Z#MTh~ zB~Qpl{0iW3gd2M7L~DhM9wRSp6~QeKT&v!KT$D6|MX}ZFM|-*P*NS(tZRIUXb0<@- ztJR7I3`@vO=|S9)%w5U%kZ3DdKX#cjAJPU6Hf!l*mlyTgpE=Wr>Na^s3IO3MtLJAW zoZh;v=1tKomw7t8H)D&q`+<Zp?nVHt&C&soga>d&}G1S zhMWo1;0i<*xX1yCe3LlGU^l<}66kPW7JXr}OTVRjDWXcih8Y_h;|#txG6gXu01r~S z2X_hk6)hcJ<#KAEEiE(UHrgWxd7NzAN?I|_x*pSMipBof^QX?gxf+?YLyUu+Gj3*8 z^331A6R65O+%pdd5m9mlhA>VOZ{G|9u^Zg; zSI8Vq$eOl4m;)Cf=q|IbW*Bajh6u6krI&rN5MX++MM~;01}`zNMf;S%&9uxFLW)FH zQX;knKJ`%zuEE3GP*kE!>v&Jg*-zwGajD6p%UT^8kfQ*ASQUf{hWYGHiCugPZOXY@ z9QlITWHRRzyA(O(Yn}42sWH4Q3;N3nbRXz65XyvUH4fzX5&ibj=@*zm6EAC|-6)OP zHyRrZK#0OP+mTC|vf&iqcmTZ+Vo_x$Hy76zT>h?bV9g~M-fLGGby|vh|e5irLobPpgM)6<^y_e+Y;j7c`B| zeG>Jpu`z%tDza;08IAtC_VggzrcDhvgGq^o)hV)LM|hi9Jxogz(fh{odF-*-Qww*5y>{i_J;gCS&ld#iAUIH4iRdxqwcv;2F z+khw*kjx%It+WIOsu(>J>DVksg=t|058CxdhRea-{lH!BQ@H#Bva+ z8zFij;s`Obs;CC)D%q$%#xk*HUXIbHvtbKg*3Nwqsgqk+qXHjx5-c1LLA617Ohmcq znFaA~B9K#bORx)3p%GUIv;`hviEeu35l)&|fPAfGIJ=SPg`kq#*S*02DL*VOg%^J@ zq^R5}*S1wONQ=M2*Yf7+1_$5D0l;(*uHV>ANr3gJtu z-B-J2*%djrp+wT5duiMhKE?-xnl_m#Q`;nfUw|DL`s=Dco`=FQ6PFgJik+|vQ5w^x z?FZNL?{xaIvgXxf!-m^t$wem!Q08}xVDv*X&HE6JG=WE z$+-ITcWHtpK+b`}jDJdpFzV(2NEV=4Fb0Q)LTg3h*L+KU;d4zMTHE46ZRg%4YKVz+ zQ78IVj}kMoVz8{YPqyR>d3wD#v<;jhPOM-^pj2#h-|O$z8Sz$Jfye`qkj8(6d# zP?*AFe#YM?^cA=)z|IcPidZ!uos@Sf8K*oXrw1gNusXH&OC0MeKP`C8&4w*A#jyPF z#p|2*BG`yX?rgPqisBj6g19Ri+g#)@c+S8&e~gd`k97PDIZ;3+JcjBQrLC3vr%?#B zYc2W|iu-pHJfYr&W|VBU+jrmz?wN1jlxv%D(^7&(E#Ips<_RDQTaq07={uK<$h2r7%#q5M5W0#O33sMCIl6W7r?FHMYjW;QRB=sjtKAWjC^N9A~Sn zY@O_cq|0kGVkJ+1t5-O!?TqGBERio>f1F8r*>h@X%2Jv!v&u>;O~vZPhnZQ+JLc=p ze2uAVj-Kr2PKYR~ZmxY(U2R)X#TDD!R}3s5>LVCrD(xTK?+!mP;*M={wrDc}=55<1 z`9rQ426>oL$Fc-YF058#h}yzmld+b5em0eUmni3C-%iLdlOyKP<&}4*j zjpL_;636WR$-;#<CXSW zrFJS&C!r*GGMw=U42wu}d5eboZJGbD09&`ZR&CD~=Hs*al+cOOgUIzQ;visOd8pj_ zdvkO3(q&WL8yh=-+r^e}8bLB-VHHX9a>$~bEdPQo2M^@xrAw!ZfB*mrx6dqF zET!j)3RROa+f{L5bs3i||Ex2IdaI4_vnzJ4gD?b)iUk5rltV zOlu29Zeq5t3QgfJ zAVWrE-xi02P_7g|tN^cDk2Bb{DpW>Z@#%c_Q!PqNyp@f~S6GYN2z`|BfS@**etVly zM?~+#jEu(Cg}GK@UVrn4qs%^0e13N5hQFzrGB1P2@fW{WT{P`vVD|O6yzur^eToP_ z|CPimAF+1EL8be(yLCDQ=sTId&_NJnuo`2^MsXnJrseIftgR-9<21KxI5oGJkL2Z+;(bMW0k4+HT}r; zW3M#Hj=^|52?_@qULogtKlBkQhUY|9!qRFross+O=}sir)h(w1tZ z`>j*&WyZYbYZvs69BJq>Z^UZ@8i~9%h^J4T=n7eNf^zN4)fFpOc6RxwP)E;(ntXJ- zAf?QZ8`M&waCvrW$_@frmhKZjw>tjzrLlWD3H)MWwL<;xXnVk=eTpFfY48&+ zj>pKpL1Z9{tfIN^g>$h$QsYOWMH#2=7^zc5$Xj#~{IKbk{ln`#zT>kJrmS?EVM7EJ zufq@_0ClWCLW>_g+wq8mS=GY%@eCnX)zH3s-d;|Mil9;z4m+bO&+AX~T)1}um?$DQ zOGx>Gm;IXh$A5v~;Euw29GMTS$-7t-&EVN5w0a1x#Mo@JCtu9{v)LRDxBmX9YJR0w z@fm8J6&&0LF<~K;KLS@l5)d<1b|KeHCBAYJKT&CJ{cQV~xN4d3*I>4b$k#n}=?@T>dy z7qB$w=htoAcM9fd#tB1nWTiUCX#GoP^H`8Fae>rgL#myvE$fc~p8BW0Knc zBewU9khvOJLEQbznL*6)6LFIlz46LHFwjDH^3C!&eJY)o2DmJ}3X{7oFZ^wVH&?}d z#e%BtPv}NHaqVv);9)=+Zi3ku#TZQUMMO&qzg=^)OpDgzI1wXzp|n>gA|XMiVdynf zrhkIgQ=eThz8wMc!Y6Jo7nehXR)N(?INME48b7@go(Eu`S}^9Si`k{yb1O$hb?T?> z>D-IQ1=|mJm|TCh;{?G>4|??OCPKcq!ozp;g({-Wvcb&FQa?47K9O8TRPp}NG(QWg z`LCufE%_JIxmA^pW?Bb%4qf5?>9c&(#}}vS0sEl0iI-qR_~i8OFnMBf&Re5a{Qfjv5eW%>g0cXf zgwSh+w`~j7rLb5TY+U^7Zv|Rry~4^-)up+{7v)706x3Z@UI6a6f`e`=^lt$YO^Cld zVMG|sR11m4XUI^@5p(WPa_TDd7(}1>+`Tex@0G4u0Tg z88CWc@K#mJL0*QIGR%#L#s#4mlF58q8`x}gfl_`{wP0HD3pF+Y$yHv>j(l)(1Bz78 zA!>3-lie4>zaQ^!?EkQP5UxN>_{8QtdrYu?S;>P^+R^aR@K2qmuQ(m~C>Yh_SE!88 zUtUx!!D5G?r(S!zW)B^`Pju>a1bPOc&}01DW6R&(VGdpM>%fl;$@4R(cP;ZM}98^q<6ay1wU}2~62~nOX z?k;MNqHH!Fp(x@e$h%!7b2^bW^MqEQSX&y#xgn&=sXeFF+!liY2q4Q^Qa7SiJ%cp( zAtBXr$T%K4cyMJBMd3ZW3d7b0TJabnS66(Rl)F$ zGe7Ok|HeQbhRTpgD-a{WTvfMoJ!{0EvD)%fc8*G(&%~LsFEydTd|})iKAiqa6mE-3 zVNi7_9P%$s&3dWIeippJfq@otJUkT;EP!Y$A(=v>^Tdo;hEk&CKYu)$_g?DL#4=?~ z6Oy@&l& zlj`aO@8k?+v+R0Fa|b$;-PhmUL*}!1qT}pX$IY!HT(q3Ja;1Tbi=;o^b`g`Bu~|f8 z=jOoBQ*q;0l=fe)K#TGv2`v3jvSA>9Q`dWv#+2=pgcuhX*1oYY{rLw-%S2UYdW!Ga zgO3z#4hjirAUPj4rv3Ctcc$^QJB8sGF9Y&&5eLyxr>e0qB#TA01L)* zYcFdnPQ6`oNMB!tr|7k><=%~pOJTp0i7aog5{I%$@&(85mLY4Ha5@%505?N8>aFt= z*&s6>$;Q0h~@vW*do%$I6O z)5z~y6ayi|>V%okse}x~;h3Wg2UI`b#4>gSEV>A1)4n>lK}%nJGRhjf?>y)!6E8u) z(;}5Y# z?FznAln*}A7XN)duvskrLQ++K9nw_i zsl-p!E_##*YXGJQ5@&3>*2|2r#e5Ts{<&U`Q{VYAzH871uZ&-z2u8fKs{4N87s));h2M6il)vTB(G-O19`Se}E$b3-Bu3PwDa;%k9ITDo z$ZFR05RH!<)nBPRyD{ZD{SaIdSTDD)H2>H-_oEe7=V3|~jBh1OBgt0eITdwGH!6?T z)7|Y|a_CWvy&1f$6S`+45JL1T80dl)4{e?f*WHreCgha!?K>Qvbd5)KytJ{k zUHN%h^eXv2S$IdKq457-tl~CDF!iifWUPOH)Pr`=cb9h)ZHmp;^?jlPK za@t2!RT+|ac*Mya(5y`+ve*aZ_tUKQZlw62^j0GxJ zcLjrI33;hXVeF?bnVLk$a1>czxhTLG1RAC{ z&EorkAt5$h8*zMoz2W*N($+)RI;7DlNzbe?N5m`*`y~J3XwH5*lL#Uaf+zU-c&K~| zI_ency|OS;6ka?YhUU+NIi{)^o3D)Sl&W{BtFEq2oDpBvW{whlaX(^KNc#LrXKQ>< zUBv_qv!>;2r8Q?cyx%#9ZAFdK80jSI}@gZk(aMn%DqwX08&&xDl&ut zAy1)Z z*C$Bi-Ov{F^DQh|TtUKj_J$tpe6w7t<&v)4kiov1qmQHFzFdpWI?(Xb+F%n4LUWrA znW&Kx8xyPhfZ#oZewyytb&8s}{Wh*m*(g`*N}KrE_Y8?$t2{dUr@Va?<8>{mcf2|3 zqLorE0U*;4CSiO8PWH$4lB?t2>@zSO^449v0!m9i*O%m=0y(X*FB;1iw8HB*yxHxX zV{GZvNB1{V=mXb|!_`o~o40v>)S4{-U3Fmh9zb852;*6(ur02g|Ht< zb?H3Xjy>Vrz|o!a^5qcFO0iEr&+9W+u&b+!kQ=6_Yr+AOsFjR^6@C)DYztrNBo9KZw^vpBtxZj#b4MnQ7al%3 z%Y>D!r}@EdU&@99nH~dWu44(2ji=&I*N={l=CVv6=wJSKT;Ac!#JI;6mu1g@xY@kr;|I3$PG(udr z32hhv!?#gKpWUG8lWs({@oII^lR3ka?2fZF%kV zAC7J@T5xWE-MDLu`hrG1Ckk;o2K3&T2%Z3V$B*!{feMYXuwcpRWISl<$@t+aWR~~C zZ);_$32bryPru{%6{qJ&w@%(F}+D%VqeI9Rb>l^hcoZ!g5Vx@t~rN zMwSHe-gxC$cd~!I5kCv7{3U-Y=Ogy{z21*P(30di3WtxQ=#7&n0qGT2IPCfB(sM4Z zHgVfsE?=d-%?GG`Zx#R2udSnFsIR|Ph^F)r0uRQ|t^5HzCanS7_er3(Ea(r3lczZB zGpMCX;h~AkQF#ujs;T`lNSKNIw_IlUQd4_n#p1W)F;P4O6%@?=kD?f-GwlEcFEq&) zdj*eD-2cB^%l1QD9eF%Zj}xZj`Rb^-CZAi4N~f8Nx{V0&F?feb!(d&0xRiw~e;{Kt zcnna)`!O#56$XDQ6z>bD2u{I?fUwCBsR5MSFKhsT6YT0D9n!d@qs#~Xn^}RjK_FuU zCW?_A^}P;^ZCO#!N|tpFyU9KxuLo=v`l7!ZB4W=J7!jKz3`Ysk5o{0N;T?_#LUoJT zRVW5qAVEWg`9Fi0 z@$TnQ*w#iK)T}oSinG6o`9cPAC8BlsbYQ@NKHB=Nv`YD6g2<4L_YO4#$bfn{)90q}hQitQG> z7d-Ls`o7IkI*BmbdYIBB$GIBbn^#y?LJp#+Yup{Qv(%ESYx-fC0_cVT=5?6eP?u8_ z_)wnXthIwa8p<_v#H}8;mBD&G9TROb4Pl^oad2}RLLLn$Bci&5NftE5s_ae#?1t<+ zo-uFsbGd4z|BBIa7mW!1fznaYu?jilamDBi{T5LO$^a_M0;+< zGKzvPdIPs$Innp&0h(za0Y;*B^ONo-{4RqNxAW!^ zxSWSDNA5xuc?rb!;M59G3jx5XOw*9aFg@0Ce_vKcIbb_O&xAh7uM@+$nEsJBNRw*-SPC z&Rr-)5hrDI!HVfne{S0J6nlrv7g$(W07YCe&7}d_+jyUjm)ygUQ-FsNn5ge^T**&1 zE-s>cMT8h2w}l&lsqu~PhLoa9f!D5mLf46ifq^YZ2u@`R`laZSRoY~oLPt+iWU05}PCOjq>PAe639f%)Vj`>xUf>}s>3IDiQp8&V zd?C0cfHmS)!ZEABvxX>$k}PFN9p|YldZYFj_QTig3szh?=OrjIph@lfi>M(XUwG%g z3gL7%gRD9^*8@Z~0})kFP%sj}XRIkaj|(TPt%>d*;a|d@0so)xd=$ovq@6}`LJDmQ zM1p}8fsu(QK^k-plV@=3D8;*_DO?iLi^!n$k?-NX@ZYIg_oD1Iv~N)KAfW^O*M9QP z50h%FtfH%gwFRRRVy;4VDcX!RCn-w$I0zA^h+qz|!2~$bIn40GsRire01AW0$JsY- zB<%t!rLnkk7&9{+$mM(k5lz%A{~>y+f6h>Ox?qlFhad=r7y!GV)3h??IL5>?1Gb83 zLql!fE`%=z#5R_*Se>x10{8_8J~4<&VO#`+?v1k)zjWeoZJKuoCr6&!@I5k`oH)00b@o&H_U9Rzbl4e8qj7o=~?EmXR?8d<2U)MSeY~ zn?RH-{jm%G2w3Zy4O__>(8T==xhP_VJ{DKAqfBfag=&PDMUEgG4@6oSudJS{gqUDM z+$3?g3|8o3u2yshU>O(Cc1b7)2nt)AK;e%bWoxHUH)5s+2nMmGft8wTPxVG{1`YBj za&lyeLZWi6cC%wPapN{g#4GX60QL8-qSyQ{8%Yc>NkW98vnhC)Qu#CECzUldUtkai zVEE@BKe&c=-@Fa{F32j%7ZnzBrXp7IG(n;ORfPCdV;4v#)6w*Cs1T?-STMkAJkHLR zu`utqRT$lZPZl}=9RRHXSRIyRPEQ#jFepss*7`TEv02=6 zJf*Unt3fV%3?wVTSVO%8f>t<~)MY7}K!=`03|_Q?;^QM{(w(aDBrh>!AtVoUES#GN zi<5T(-~}VTvvlom7EFn#-SM>)K)rVD!U9DmX`rG)kI~Fa2p$smEF=JzYL6X8*8u5V z-~8V}Lok@idmw@Il&oJ9&}!%@EtW5h4<9`$j1U7=>nsBiia|dHw8#PhL>JSzh6y-1 zpp1t&o0XYZ3)X882TPmBRC47nlIhL;+0g z2r>o$8KH#*MEhP@3XK7^1uxozl&Q0bv{)4+hGD9Mv;zNv1-Q2CKU(!k9Weg+mgkxV zVAf+;x1dG!2$VG}z#{8>vm=3IaZNE0z#YM(!Hn!MEUl1z<5RfhegAz+5kfxJ9e6aj zokLDe&+#V!;~+*+=vn_sx&`l+w0}f@fGl&&=m{AW@Gm%s`Yi$Jg4}JA6D* zkI>FxUQLvdDM}B2_Vwuj0Y|hZU^kr>TUT0Iiqy;GpD8ybYT}?K4jkZ&VF)UA3XNH^ z`nGJ*ca!C|{O7&#zD3G`6coxz2*q#mHrAlmgn&p<@CF;4fn4d^;~0Drd=TiH$RnIx zcg8?$9nX@i3+g&JYyGEPkA-~@cM1hQy!STK#c2eEwieT70?5R{D*|&#yey=(h$&$Vxc2*hXqZKLCmL>K`Yqu(xj3AqQ0A)^$%?&I*5Cy{S1)n zzt5BBMAB!JVTfaR*OE||1>TOHUi`tok0%Q0)#da;8R91#BXtlY(5omK4k0&#em~Ml znw>WrYB>}nxC-$7_z*6Un;`4O#$e>7Uu{pNvtVq71oO4f&;`{{W}Hs&(Io1b2t-Ih z8*oSx?L%4b%639xLt#X61;}&)-bXsdoD|P`P;`kBB&Jjp8kH3IC??$XxpzuSAHhB+ zP6ecmiozcG7!IJ3s~kEU0;3_}~stT>4t ze!9G~$4P-w;E@YCuBXT^vHUf$nLwwzS>M-Xt@#`)fw1{fQq=HkgjNQ9Od?IU96J;7 zg(?kGap2TrZ}x@+1?l1cMC_0R&a06Is@LHjdn7Aiq_Y9f6j{v;ZM z>GIw40ThK0;!*(>00y7Qd2J;aLnvbR&`rjW+!HFZ;PIlCK(Rt18OUEC828-Q;sq@M z6lfxM`fh{yXPh)A*aC=82sF%<7L6XF{NGst=%=St_#WXK3Cd$MZ`bS@@&*vt^(7}% zaGlqthT*tDQRxaE2il7;pD@9eMFQZrq-_cEX_cbCUK2Y{uu^9Eq1FZU^BsqMaC{wx z^fLkf5~F0G-cTHWLbWR7a;?e|%nvM0az5bsKe&Hic(Iz8^~XJ?!6||Vxt#Z-7nl%2 z?6Wm8;|Ep>Cc;D}1ejIi1*}-HSQ06>w4dWY5UL=HdjKl~xLT46W60A^3ENBrQFC*n z|M@mz*s;7OBpjtZX-q(DG?APn&`3pS2mP;IRVNAWfXHk%F3wZ^z`*_lAgwL zsxrWMz(Dh2(nx3V7%_Z#*Xrbm?f<_GV~S+*y2Z6%7?>cy!Z)=6ywWb`+(;agi$%SP zD%jqDhOGbygA%ocfLXwHQ27;wphgmA(qu)W;}8-R)IV^T-3GMnz8y=ktqI{C4$}s3 z;KpeT6>r1EN=kVEZjY$*c&Pb8j=Sk73hSAfiGi=5%Q6%dq)a0s)pd1xI&+t2tDdyoRhieOs9x+1vFwxS+Al28+5RT>8MubET)nO7@ z$k#bIbRDc>WkXL1wJJ7fWMt%KphR%kp$jOhM4Q_U7B@wF-}>#ws?U}^<>7zTqR07V_%9tNckU$-}gBVItm?&DZ=4{DO z=!g&N`V?eEq->G-;Szz__d47)a_Oq}v$U`TP(QJE>``6=0v)+o1oE-%?X$O;qH2%` zph{Dsk(#m)tp8uPk2&%N+CzT(7WyvOjX&TSfrUmYOg!_c2bUO0rzk@UQ4_~J^GKeenKuoEmp_jO=@?X4=8@)l~T&#cXJ}E ziDbDqZvwL7eG&X<*Y3)7zKe}Y5mXBcQ=tpOh!bp{gxG-diAZNdP@F+xo%xn+>ybV{ zmIv*F$d_44lp*&w?j1p7g;JMbK@I`mlLD(9Kb{mNfKI=Jmmt8G_jf0MXeIH=#AF-v zg3)ckj%H>QCySDx|8ZDuz|mBs4i1DXPV^VRmOL?ieFR(t3^`zkEOOPe}J9x|u|2fY^lf=cGMV;>d=q9@`D@(Fbw?=|_L za>0F_MY-+r4g^1sM6eKP^vytv3STiu2UHp|5=67*(4j+{al0q$`24Sqjx$76Ps)+B z(ewSx+oHziW=$$xF??jOG7z?rfD(~crV^;`J%t|w9f;zH7Dao|r69GqFZC>$=+V5< z>>^zR499d(p5m|}GG=64ynKr7>!D@j9qdfGzDxn?pa!Yh%&Ok6UHWc9EGPvjzX+oA zKM5ete<98`e!RVZex?;}EK`X5?`D)E`d}f2rAIUxiSI8?SEOU`G3ViIyZr13JNbny zgd#-f1Ri?M`h7Lfo%@Lp0;^;{q**T^K7l8UMV!?_o7#zmaXGF6X(|5x5{6{_M! zZf>H{?E<7D8cODG3fr+LS1b=h??sDB_LU-}nTJruLu&^3*lHBJ#1Z=!{J{@F%i!Po zODk4Q7Jp1GM;>4uFr4s=Q2OC0U|{Yt_kI2PH5u!m{D+AK+2;Ve`CSQv>@<0 zLd`>?3;DYyU^OBc44=_^?86BDE->qS5F&u=JvlC^b}0XV>}DWx_fsoz!#?9zk}AML z0_k23y$hgn;DdwBD2c?ZSXtL950ES5j?G@;LwL2YRuARLSxwy2`+-n|1$NJunv*E1 zsmuQJjtwhdMWRufjC z-xY7=mIUGqNd4nQ51mj1aOnnGI1%8KeB{u@a?Vj*i zJ|#yYAZR5Kryw=y%1ihlYE@DW2sWh}!4W02_sknHK1 zOM0(wgDEbRoWx=bv?>Usv95?;FG^QP1wK=G$5#cR z(mpq+_VHBUpHPG*DtA6$KfrN^z zW)!LjSRSq2&%myR^zvQ~Sd91WTiHoVg&hg^x142l7!ad-#I_pv1mnJefd*)(mIW3d zSIG8{8MBU!ZI^caWm@pfn3@ac9z7}0=Xe3GLE$4$GJOc;}K+kWg&CL_xh>!F#}-eup|@& zA+Je|9IPvzkO=Yk@rRg9WsDSv&aZ;TB#|==Z>H*zd?K3*rii`)obC?xuV}P#3--D@ zc-MbU+I23QQ4II!)vKHTu5SO{y|u`-7?!89E;$%sxzmSi8;i|o`OK|FtV9;uht=p8 zY3lb^YdILo(1ag>nU8MpL`aYmIgNmbVkp3q+*n>`#2SoOfJ`aG{d>sBl^#Tio+$1A zSlOippjOiVC#;R!8VVA?#FQoM2Gr2BY^#P@6u%PS2?}_rG~!FK1CnrxI-VLJ99B|2 z*-l7;hQ<1ylQ`MH+}3t)$-)IQewt z9OW%opo9jiB+3A>GYd;U0_}R#LEJ;BI>;cBA0o>N9ph&~OL|mIU-_4T!GH7)(3oJ! z^H}CUkAf+>w_(~u`o$3RE;yJPZ(iO}2*ObG{Ng7RV=qV8r3WqDYL(*;uZWLs8aM>o zFzo86_jmvdm~36xOF#(;CFr2mKLFxP^htAuIFkVYq2ED>06$e@QKDL1(Qo=G>cTx~N|pj;u?a&%j&mZ80^oxU z$PlXt930Khi7V03_9%fM?4R*&5dA^w?`Ji}%nQVWrs^RTh>Bt%9)DN{2Y{#mP-5p- zl`{+E;pQHnYhN-Y&Re|8_ehAwEn6-N>Jm^K4Z8#>h1;=k0UZJj5=Y_;V;O8l|8Qm1 zz#%9ZNV2B88k{=iQ*fQem;#JM!Spjym+p~B8V6vad4X`saJZP z7=;}Z$R310ZM~tq_tQJMeZ`@EXte~@>>eA53Im~DgR!D za~se0?!9|jaHtYoZVg;2#sQ=SZ9;=3jc`i@agS$T#UT-k+@2xE9J1MEea{*4pav*72hKs`_X(1Fj?12`E z|M~Vf6c$qnr`7%dlHAz@+XRi3V}MmUsUuz-oOD;4=D#*sE(V5haL1x z|Mf|^XuwCZ%}^bj(#yz~ZXz76G$q%drt;tYmqG1DIvePgVY|SphSrB%wrW1O9C0C` z^Mbl}fyKb|^uIo{V(9K~RGs|ScpG7>`S(d1AR&QiB*q(06Fl6;e}gjeQA*KPg1}Th zMgRG5@z6WrSWIN!Fh8(+_ikHEFItNY|NAGYshJ^R!6(H@n4o@B4c|t<{PknO`EhYXJI82294M~R*7CQ>$gFuknK;J2x z_L__o^t^#ZGY{^y!xD%-h4@1fl9>Qd#8e6JTc~sxnFT?CP{>h+F`&dT7!fToV!`uz z`u7t%tWs*LwwD0-+K(>H7~#?q_$dQ3J7jE}2I&LA&evZKGoMe#l#gKH+wh;M>yG_` zFdcwAwgB*fMj`YkJ)x-(YW!#5bXBlppf~aZWceUkAn)P6GhGWa5i4{l`Zu<;QHzTK z#7Yp>3MjxjOscJ>Z~Hm5l>eEMpUyasEIGYm9pC?7T7cot zA&)k*%`XMIJio3Y62$0ytZcm?)v?oz7pPA$Jlkz!`=a8?xh(F?vx9FQF7_xLl9_n4 zHm#xI`F&d@xwNdbD7~ZUMzq&9((cvVp{co+fp#qu>$Bnfsi_F{P1_QEKNo#8Y0G{n z@wz$LwZ{9_bLCXmTVu*sNCb^zP|j!E7VFkXe1TN%09RW{O$nlUds~{)L5*`CwDwmp zzC`N;j(=sh4Nz5MJVz$UHUJ2hQ8$meMSVQn>mpaUWV9C-7ui3Zt?WlhDiRs_Fe(b= zJS(M;nD_wCCAcX-@GHDKVL~3j{%PuDp_dWnY8nPl5Fh7Bx@sd-#hZg%|*ex*#pZ&C`?c2Dm?C@Q0+=Z+3eRuDTZ$y$4m7 zuR2HsIUgY=aU+0)2+w$A$Ohn#>cY4&Fwo6>6biKvrDG0RN(Md};V=3xY?hU6d^Cyn zh`I=2Gw)L2rkFOg6cV0;EHDdanBjSh;0C%I zRFv)KkeUMOw_BW_A%qh^q!u6Fs;a67pjdG|6q}spK{6kSXbZ3w1UddI85z&L9xU{m zc?MqNz9fZ0$7P~TRk{jD_5&14Kr&(E?EF+ant$*xO$}T;V7V812~$^{f#Q4vx;mWu zh{eqyGUt{$6?(#<3Av{m1QVMvc`?+b04slBE@y%f*#a3SSg4R!+WXNNRDDdREv!={OJ4QTzV z&gG!F4rZWPL{I?(X>=Og3po`&X#M4P-6gNFzmNzK15U1+(*Y7M0PYRYNbuaRE(w)H)iSuAU|&#_Tj`t zZc+qGY`|o!BdMt)RrVvcZ$xGPX7I&t{;dM9OE4Hkej$#p5E2sNma~g3r>TK7Vl!}} zGMwAE!I9k%mmw%59-gvpy@ppfrS7&@@hdp1W5Tm<_;+(+_MoEy&SHiW77DkTYGRGu z6D;+;k>!1YQm6sI8Ni}Do+p5su<-E3-gadFL~6l~2j>`Wq)kQ1AgjB(8)a37;7p8; zAOB%STaL$VY)GNx36a&Cj4n#V!ieN8^9u{GQ?klADxyPl2#CGKMgC1rr?0TN0mj=$ za3h4Apxnu_1;Kg%N{&3P65xn3LhO`ME0PKX(XwIw8#iiiZ=ye_EDTudQt;P z_fnSa&|N7P=>*z3N=8}Hf*{!LmIlGXn{dK#J zhK9yL){d@T5bXH*Z*JQ(l*~^GMS!^1hDAgu6%tZ|L>nuwEc)fhr)BL97NN1E5J-Y!Uq$QB2F13FtQ^?m42?D*UtI5$oq(DR28&_XlKa$6Fi-S7Gp`uxo+Yh3npILFM`sI~Z0ZP;ZWt@>S%7$&j>6N7;ZwwkO;`;Fu zcrI&baPZzwb-}lShrQH;MD-HW34xuoLl1|M<2r@eG&CE;hDWkUjekkCjR z$Pr{Mdx>XEm>QA>;9?yoZkG2}n^(qeN|d&`M2bL>VUyqjn!w2m&JffPa{;1NP*rV9 z8$hxMkWU{@FVUoEk0>RfaRU&6FLIg7jleOAsQ)VwGh@n?3pBmHEVL_}m_w231cGxDwk> z@lyOv9mNy;(Cqs^mp~3hpirW8#mQQj^_PODPTo!wpE%Pt3zj}l%EsX@FW`l!j(`<7 zP|4|nCve}Hm7((_D!7RU76kVlFXt3oe(fc}FsX`JT$r2ajxz(wRK1NS0`O1)>{OH& zttX8w7T%XfplZb)ryHUJ*Q&F6P!J)wR8fsxIw<_j?j@AFq>SXpYfoT({g0>uW$N1_ zM4%I?!{Mf)=rtc(TWd%N1%ht_SV8OSCkS}+&C&z~)yW8h3zj|ofpyqnnwHkKzwtq$ zqWi<4lBEEGh+)W0n-^LevMpgO5J$8^P{?PuRzR3e#2xtF*`JrUkApNExlK*08E=Db zkE9d!E#>c?EWd*&+h8CL?uxwVMc`6E?sUdxd@HGu#jE-hYzc$~zBM&)F&|)T z>s=#76gZI@Po$3%2?ZCfT=~LgpnQi&dl5xIfs{$rDN5!r&{8B2v!7HW!ovFA&UBL;i-PVc$&#&>#VhS<)Mf+=i+Juz0SoSgSD{fR;cpC`~*JOlX+ z5owY}<HcJQ0 zdlA46%A3(VC%F`NWklx3u|B>+M||+e5qaC@wcOkfiNOx$%G8hCU^Ox9nLq#=z>T6+ zS^v0(Es=j9>yC)CKXZl%=;tPKQAQ#C;w%^zxYS&1Zq!m&5Bg7Eda`uIqASP}fIAmi zkpLUc6xdY6OIecon&|IKP_!YQtGzFvuB+5(rD2OE&tUMzemEY9;@sg755u8$rXO0) zKi^&itr~O0v&lXEukX^r)IfsGEw0$}u1J=M=%BZFZm3IBXp@kT2D;MLr|ZPfbx(1? z|J)3gS%{}bW(pWquB<0!-6-7B$ajq9l+r|p@uk}sV&_vQ)pnSHDM)4B5V8$*`P+-9 z@1jOYV&$%O6$M|A|H#KSG3Bv4F%<2F62#Q2bA@AnE&~Gtp&}X)IwLHmnrkJ!6mb3g z@^-!IvZ}@h4uJVkG9I*c7kE4oIS>#|o~!LIj&AiCc|%VOI8yz# zOdE^p#@{wd)9ypAM>9EC+xWnEf^-A{ACN)qm~V}JWe>JjeVzw#@}X+mal5$I4Xcfu z)~sE77d2gdQ2U4bu0@Wf<{Oy7plk+_4q)rIZ0XG-V`B|i&&2i3MLocY%(dyxh*mpO z2~Q$y$I-$3!BYrH7xNH$tclF-fYVwsc zJ*iXQCGM(;;rxSX?%LJI=s)D0>mo0ibMRbDbxouH2Kzv9CRT>Oals)W6D_Vae?xNx zVBFO^DiMNB=Lk5Zumu^ASH$(9z|HPFrc5tBH*?^K+Ey%WBzkUrPLPa>!w02okqc6$ zSy*wMh%45BW~)&+TDk1Rj{w=SRG<=W>OHilrKcajwf6X)qW|HKBr2~-KQ8o5Ip3QQ7`P>h zY0*h!7^u#qLywrE_>er1TLH6YxR0?UDxAAZPAGJx{_tR+`ojnEv^SaWaipW7S{`k5 zcLzYOaJC2+0cMJ3#h=@V;0Rs}^WJlIU30KbaP3R-c9KPYrUHkp<(}7>(W;dT(>nZi zO5!3SyWupMyu+!jWq4;CX6ZO)VW8UVFvz@h+}!;m9w+l%wC1LUJwK`*K61pkj#hJg z4~qB5uDr7B?Yr^R#lF;JX|IrXr_Om#?QwdA6ASDuq1*J2wWCLe7mpRF%+OmH_9C=E z(@&TKoDiF9B&s|=Qcft727Xf&{8P4=nXG=|SOCnzkW=3UOBgP%3Bi)68q<$fnT&7q z8>-Y@PBoB-)2K|~RPHvagb zXl_hB-;%#({rbreS78N(Z)XO~fOF_4D_Gc(Uh1S5LgtVs>Q1nOx=-{U!n*-&mT!CV z5uqLket1Pi;!H}O4I(;BOsb5`>T{F3-hw@VY4iYyXQaQ7b0(c|%Vc6;F!b`uL%=JG zV-n%w`!i!oDBvP>kh5I^OM7>{Wo(K^HEL#74JstSreZ&P?VU9=Fu*gufL#sN2}ke& z+EKg@5GpFXtawXYG%=-fZH0r>FHn(C04PTNrUAl=qIQ7L-I)P0zbbhauzeFO5MJ^L zre^pMB0;WETWT3m1a{o{BD!Tt1d~+67 zQ&w&{W00(b0$aFD0)taH%P)N-mB%7I zSqOYuizP@A2&u1w;t1*exqV$utp)DH*^PO-8luk3lQQ>)5$8dN34FuxZ^u)$rZ7S@ zY};17si_|v2B}#C6SS6jZ3qEKuwU-9GC{QkG2%m}Ft?!6Y7P|22&)c@GDX@a3t9~l zZz7In*&1K=cAOsvmYjay24_HE#CIH_`njacKWY_#6|mcbu0M=LBWiHVLGeN)4s=i! zAay;wz9WKCnfVoyvFD?My?p~&`C#GpAIUbIh!^vR=!6t+5+0F{@9b=II*|}9CD?XqeNE6wi8kkFPNhW#DZwv)laCX9v(!Q7H&hP*VprOzbb0@GkT@U(ew7KhCQ zR%}0FQU1Tqn%5CU6Jc@){c2*9A0w(K-5SmbxCk95Z1V=6;vn0V*1H3{t9$JhCW&I9 zaX~67Dn#ybtcJV_5N{Po2tzGC8yMgmac7YE5_@>!K zlZn78m0w99&l|_e-Lz#(m0LWJc{y2mwC%YH)s=aF?%eF`cxQw_e{|q{+MclJ6FfS& z58`;)cYZH65qC7x;XdvGnN&tk9-dMI`FaAZ@%uW;%F6Z0i@UjyGe%A z5KVr|R7fM7b)Fzb^wsjmc<&ML8#({LJv1zg%clx5ozt6>n+H7zp-hslO9go@-It6r z4s$(rB^J!Hxq)-?P#OF9nE*N?u|FJk<@^`qN7>sQObE<THS2{xTgcEux#?@% zUV*1CrI?{%U6qBp4$@KSA$Y%R@o3>BmI7Stn$f2CM)zx zDlHwio;43lPzkPvyib%9F}7#C&C227Y4o=cYvFsZrC=@C{u; zMLkn_NfV+`Se(^Z7Sp>l!cy(=qa)eerfqf45GNr$kMC@Ue1Qly3!h0K{I|0kGPd!{ z9I)5iwM!29L3x$HPM5cxPVy>RD5!y?`K;FrWGBEsS)^GRidr!xAx^UNnt=|+d*bO^ zG5uu8iN@Nx@S6z~=%Jko=Hiu5`asryXLkfMPX=0KS(b7aeV(4IYvn1n*52(VdppVd zs0-{c0ZPBKAGn*F+thgfJ%UbGTgpnA&O+c8WI|z|MlUPL7Wc*vxAP*AIEygB$y!YdoN7HJiA^rxM@cT=*C8WV}FL?c*S^w5)!JgEcBTzPV1SAB8 zO-69S!uoSA>IE9cUVE42Tm1g`T)2Cnr^m+Y#j&JnYda;Cci5_!493_%(9}|-te+U8 zuy*`H--S;o3y_>>m2^5y_k=GdC1r43JNr^B2msPit7{FdW{W8b$vdt5tpXC!XREw@ zt@iHSqd0HOgmGnL?KDLGX2!qT>4J{~nYOdnoCrQ#zl!`6>t z%bDF=5JQ(UZ-Y=fpr*mW{e%#LX`^d;h zK!mbPPk1hKf7e5Q_g`M}KJ7qxMhmF29Wz0GK>kP*U?$2sX@(kwrm0_fpe5dneCSiY zO*wycRo_|EWqA4LrVhV$?hLM~`u0hy=}+OsTi6rZMy7VstYLr-MA@TQLpXAWG%%Xk z))6^ZN6rMdR^x>4O^f`)z%j!!H%YtlO~?Yz3Lglen=Xw#f-ls$Dn&Hasg zJyzb%ptCLiGxtew4r=3L6pVxhP=sirkidyf3sULnFHpag&)KmQjY zd?r~nHMMrd+uL~Si#_HsPgZi52AO5T9^u4bMBU)usi{o9u8o77!WBWe{PLJo_n__C zRRz#^?%+=Fw#;5!yQ>PP$j8sto?IEQot2d209e!;iu(mrJ@T++KC zP-c;Ps*;c(mNMkwI^_nMZ6y;E?^Si%-8in{*g-bn&8tR?kOhLx8oT7HjY$PzCzHu4 zkjf9SF~>QjUh^HlutpdpUyp~0TWc0y!`H7FXn;ed5{2!6Sd&PImr>^JBN68wpAzdXh(BU+TPf`^r`02e9r9a*;0`PqoEc`b}Pfq)F4&~zmhsGx55`@^VI#bsp= z66CC@MIK-+({^9vka_cGqZ3AnbX_}=v-3-ZC8Bard8l@CQha1OR5+$@JmmxE@iySn zMD7)1*Y@!L?Y~xlkX8;zLU|R(x^?HS?yN%!z@*mgU}xuY-@@3$6Fja%&k30UOCeG7XiLA4}O3O?$3BggB9$L>h~gM0kmzt-#up>8!i zdD6i)A3zdzr1&30Kp`c>X*HQ>pUbCWz)7cqk;-RWN*<4qJXqNA(Q5YO!(URCoG2t* zQE2pULU+pa^tU6!%mS(>SF4P(uA`s63cYbFiYvq8)R2KS>m4HQII!C*uR4)+m~h7u z&BdsfGIo+e)1$*rPWIiX=z=_6&%dk|#qKD*-BmR?F_BOp6RtKK80KYRxE=-0zK9>SAZz}RY7wFJQ>pEpuRD* z$2xoGlT(wO)+h{o9L9&%UN^V^OR?Dm*^j6`f>v8kMJT3;WdBjjYvbw&h#i zxinHZphazpYA^!=B9ksR4XtlmI$5vM;2=l z;24t6kmJM9w8+X@y_+I7NTemj8Lxs(tPFJqIA%z#N#Er@SW1n55RT?t^eE#K0W*b= zAS2@LtM3jF4JpvaF@jJa#?upss1jF(T#rpkdW6h1B5nYBc76S*zVO<1G~%_zSaVCC zW>~k%>l(5HQbPd%%TPTie^We^fsf!g^mW_R81lbx{)eqU^!Ebv#XzJZ%gc0ZM+nHY zI>2QY_KjPCi{7w8@^zR-3ul7qllv}bt81_Q@xxBh*3-jdGd9)n08$$O%u!lSOqPzG zt-&{*NQA+RWNZ({10Y5Dq}evqchSAlT)=7p;S-B%l$E+wDn`Rz2lWmtTWP?}yhJS( znQ|*xSauW@N!;rQxVi06OW`l(fo39Su29xboKOP0N)8{1jnKVZM_AwkHEfS<)eZ!e$Rb#(m)=w3r8zgNAU=+_R$c0 zYe0@-K-Fo`24|j(CrA&B-AL0US)&C@)CIfG0c350QQPNf&PcQL(Fp!w779o32p-!1h;81AQ`iOnS0<1&ib4{ z2uom8g39BR0dDfC+O?d=$pLa0{<`=wPp5)e*J^Hn%AM_;*bOT9dqAvk?{rB=r5TZU z#6}!yKY~_KP{HN7bHO>0NOtfk=k_TH{Zo(;3m$~UNWil2(8x+bkhEb z7P3~-4^J<93-$&OG=Or9p=*Nrj*vnSh&(W>YWngeAs~i{`c6|bg!u&dK!~21B_kyC zrrVV@pZHlb^$zb8e(aTo^TZ#@;f$u|$Xehp_w7ticxq}Y?)X6j<(44QI-&|zAE&U1 z>N?Myt|gm8qEmIs1K1S-1sS_=wl&8x!uoS^U*iZNNWp?Zwca`p-2M`&fl?}bLRyIs zDyQL94Gcw)YjLXu6dLfwKv9=L7nA>m!_1Eqpb{>?TSHi|v~vJ05tgZ1Ck7Qm6rwbH z9;4ztTL`Hq&^wqwfS?gKr07qP?DLZt9T7Kzw`%p6gZAn%@y;z^SD)T-fzW_*KCpgovd1sGXyu$9E?`>{Z(}kB=Se@LQZnPjG*_8Z?rRkpU5BMQ9vVT;@Cdw8x`Z?Vfyo|G;UJ< zsQTjNpXK6w{QjeTcG2%qvE+KsT`o?jYJ=ehyK+!~J*wT&%10?h*}HzrWF`dtaK9|@ znRwXj*bc*a3%h
`VAMe+?=o4>X_3#$X3Y;Z)<+=$SD5gaw?+N0$Ec2j8r!AzmG zUu`SjgA8^vCMpiGgOs3Dcf@i<07^~e*P#|Ji&QazK+5Z$MA6!^i+kXrGJWS%iTH!J3X&pjG zE@Xfv)hk(A7;g0t`JIs=S_E%N996XRX)QgSy8)9fF0?P1ppgdiji2}86X9WT3Q}M8_);JSwF?A?a#R}l(`ZW8i>aR z@Gg0T0v;kT0n}qAgaHKB=sy~K=?wwIa5&|g&=4nJf?N?3L*jn_?Wx7V^&M%*Q%P+E zkkSv1xpOC#gfQ&b0P7Ov?1_>p_eU`bGjXw`l62WNNLaY2Sf4;oz*kYkT632EJFGws z;;CZGcmSrw4(QU!y$qqwo){G(^MrByJ#^|k1BwnYdb)YXTB6p1j}TPl5azWMoJT=b zHfrPW@C}HOGf_4KQ6w$~^#@MMVORq&W+SZ}!RnKe4uIOIhIceR zg1DaGj*gD)5LC5V&m|wC$Dshte;^d#X_Y2BM~f^nhqIVK>@WY@SiP^pn)@1Q;_%TJR{q&1xi06Xutqr1-KX% zTY1=^T9$Zu62UKmQlia(l@;MZa8l9x&*3A_Afe;TO>_kMi0Z_E)*)2%?oo;c+FZN~iyodczO1)qX+!k?JcrOOlIK~*= zSz7Kn?F4U0{1$kQPeKdIuTpPmU{F&%&~Rmm$z$p@BBjluqVGGqK~A{+`fyF7b+V(Q zBWW;%r>TsmXcH>6@mM79H*>JFk8?El=sP`xyGekv@(y|VxwkZoGJ{o!kwGTab%?N1 z580yxkrZFuu|o5jB1dso%8(6+n%Qcn0888N*fRoa!}I7VOv)K4Bp?3oBuf8{dg=d- zKLu@Hb(?`w@#57hLez!d9PIDEOQFgmwW^&12Yr2&R=~O7trJ2ek4wwBz29m`PH{{B z|I*X_FS5S>RsL4Y#&AL$l>rd8@7%Ut$32#Y{ChfC@pAg{%73?{zs+e`(N!w{7iwYr z_<=hoe=6PcWzD~TM9>KRyYJGe#^WM(=l19f#-hjuZ!Vl1;4)ZPNv_oWx@l$$`DJNWQGiO<#CBHGDTC`Q zh92a19XTu~Ydq8{YaB_007i)^#!a{WXyx)HDDQij{u(|8+uMg$2lO-Fd9pq4@Btnx zM)F4fG`;#CsVhU&co?!H$~Ndk?|WvPvHXdXf3EWv-ReHQnbmZ4*a`O}qch~!6vu9X zY@57Pt8?b}mPGpeE7y}>wtStNy{K`TiM|Ye#;?;WHZG{u`J>a?IY$=V*^b+FOEJLRz2>J2~9iR)%_#e=4rQ@d`(A< zREyR4VVp)6n>>w;9b(zl`N%^HGM?DyW6-X*#i%E8o#HmufbE?6*T$E0DsLArf54_! z`)1FQ$0Bp2e_VaK$UM)m{?YaIMxNxa<{yM~ve6F3`t_-9iB+NPtHNVMvSMBwuJ=or zcU&Io!g##{QN>AhLR;kJr(SFc{M3DZeaS_g&TRpbrQF1(l{_bu_V$mTEh^TYO1Tx@lY+3jbL;Sis4`RpPXj zSIP-SuM=Nxs7@7$eZR?m>?T|GxvfqYIlk*B)9!Vk&lb`DCE_J~kt^6?)2p?|)?QBz zs~4rR{?HT_ex0$le#f@j^Fp=t8L_X}>jT)2n;*ZOuxVGqomEzxKLYOY{phq$uwHzv z-1q%hZ{+o*Tdp-bA?2EyyLHddtHg4q@=K#<^Fw=6Gw<>rk3#?kYYu`S| zR~=aFvBD_$!en&T==E7%6a8`f>!V+SY6R`*{pnw@kLU2-73sZm@~)p@^r}~KyPdWR zO0O@cJIXX2q@D=q9NJs25rC)+w;~(Rs0YaZXE*h>tLL=yWKR zHk7)St`3R|5}?VZa-ujhi=TYU+d#zDebui6|rc{BI){#neMawE>TIH3>RE4yKRP$?&8eU$c z{}D7%`lYlc=&s^4O@9#G?G;CvAFn9DFGbC_JZ0uYqZG|j*%6HnkrB2I&r&mr|E6m^ z;w$XVukToUn=g-=fua<|aFzNAJquMXWzTs7nkkAIbum4@fO?+Si)Wg~dA+m5EZ@v3n)?bm@HEmrrakIR%~u+pAS!d=r;H4^5Nq>QPuJzG<)jWjzs8*X0%eo=_NURqW~Ede zKG)Amt6gSyzhU`lT?wmS&QFfGDwQjnlBC}?1y{V%*s;;MzIUEM+k1SvFOU5e z?KhsMW3XRW@=|$AJ6*B%JI}09<5Ta`y-c0Le%jyAd+<)JC-X*)^cM+7V~fAWcjl+r zYtBAoFFE>sd(OA*Mw6GnC_8UTqT63|r83%}Iy!8#e#xch`~J2BzWmA7?egh(Y-;PJ zp2aEgTX9!5FVc;idnZ68U_39iDv)|U@~6Sgsl*H-z(*qN4lKf_?gQGfsoc`u$E_R(#$zq+=`n7&^!?;`2(Oq9I z`Shv1{gEH5Dr9@-=@w%Ts}Z-OhG&jMO}2@A4c}^Z-bJ3F|Bhww&3aGTZN}_2SB~y^ z)OR`fcf;7J`O|Zo>w-%-8nr7{RNqmewQ|e6?d_I(n}1gJW6^J!VD9l_8m@hzw;%QG z4>r|oXB{~3zDHQ8RpS01CxO|qLqF{g^gmjcW%S~3ouXFU<^tV1pS>d6GKK97rju`9 z?i<4mt8OeYtEHQLc>C-n#a>1&gUkM>6GoaS7t*GEZHX6JtSmz{cMX8s#_nvuSs1(`Z^*WY)K^nWf}mdv^cSquGUrDJKK6 zueWFZGBX?x*chl@%Ux$$VwWlKck%h%Y=$4&*^C82ZR`WPCY@xyw$iUK+3mT>C;E2e zqK2WKkxAXY**zNmmkw__zI*k`vJP@ z@Y3S3zDIAlKixVMSl+|RlB)c&?@;QVl9jWXy=rwErXJ1As`fs*z2tVerQ-L%p4(30 zi?`P2XID2x+%}_GpxNeTY0&8>XvW)7e1hY#YGUCI4cf9&+n zb}?QlJYoMd!2WRQz7y&p+%kFhKE19klo*?_ZWA5jmvNf%XnLV>m!tOf6Rr>jTi%Mf z>40#Vx2)UV@$vrsJE8dV4IjVBiry7J`NbzPxviG?hDOaJUajiO6%5(=PI>&Lw6tPRch$5-6n#g;akrkyWQBpYnyvBJ{lhFI$Qr?VyZ7qu#no{Qp(ZC49y z6CbuWP2+a=2{gO!X>=-ITeT=L-}dwcqcWTFOIK!G4DT9lp|#mlZ20Kjx4jaFCe}%s zWQ}|BbfgiZYvvq^# zz0uBzUpBJ^UpH9(6!?80CQ|54isebKvn?4}I&J=4s@g>_49lGbB4=(|rXEZG{^n(n zt3{LR0l7!J0}pndyfDM`w&U}3+tt4&f__P(Z&rPXkPs~CryhN@U2wIjdhq~nKJSu> zo^r+ThJf*5YG;;YACK_{$Cgtq@$wVH-y3^H5`Xc<%$etXTvt|q*Dc9k$Hdzh6Gl(O`q6&< zo%}N~ddJ6^^Ffm^yNO~?DM z6%QS;dVlQN$h#)$n!uckZ~3?ua{Opt`l>YjJ#zByiz^PN9Ez=@jG839eV#3hn79s= z9X>KP^IddjfaCsFwM5|vnSjy3)Ai4G&;k=FcS|{>q_LcO9bURL8^RFH->5rT1KIK*P zIWBtg_0f&?>C~cw@5TzuuG~|lN&S-V)I z@4mOmQjNNNV^uq2U+$fqeqO)#(8Z4UA2fNxn@UdR9%~Mcbo{NX=vs6yHYz)pL8|&Z zgI+8B@7{+O1{_2TvXbV%%1PchMl;Xb=|7s|@coH+&W^bF%mbbkye3~<@?SAaWvlh% zKC$4c*mYCk=Y=|}I)C@5Czn3?c)c!hKd;)EYBT@))}alP8;gH<(Js->Y>tndr!{!= zBt1L$mhchB`tsBT-p_KM4}GgvtR0p(@$z}(lkzBg;kYfGCum?78&{G5iAku3R^? zS8P<-KkeP|$4&Lz*8$zx%Dz~ILkmB5zj^GsdFjcG8Wp!4zx&Wa_IK#^h%sp~M=|{d z*M(?l{?W~2{b%&rcn6K843w-3s`$qquUo@W!24o$r-3M4Ld{0wcGaf2q71()4N04X zPgM2{4BXuDwLNisYk1qevEnaU2{){{tY?o+?B($3ak+GDYoKF-{`1J2o5s4YxK^GX zaJYT#d7+KF%g)Vwg-cJ$l7BDc9-e5IudzPSpq^r5SuB^=osSNJn>x4aZI^l9U*dL7 zE&9`61R>ysFdgJiBk^}CVzF{f9 z_J=v?sc1-Vw0W5P-9y_Y(59a+SMSTQQ)l8PW{i!c)_$z7BEDmDP zTFzf;OZTenED#ebf6!>I%r5FX>?Xo}{EltX-7V`(?)BQaOgi!NJ?0x=iJV-`#v{o5 z#+D|TZm$3X6KnI{AMdH^dDkn)!wGCZra$`5z8?e#Jn z;JohfQ0YjXDp#srBV924&*yzvZ%#Xle$n5^A!(l(9%*eRBD+pM*TW#4`r5(7q))E( z3hgh%;#W=$8>m-C#KiTptYGVNewK3cb8b9>ed-4UH zWsaBPhs-1PfezB#23n_#i;O3@%nFkEj$ia=q!!1T7Sz98;Ex4s5%@oF;M1brnmG{epc4jXYQil*Xp3KgYn3U z!&f4=w{Pf=uKs-0=9anRrbELU9@#FPR(NA+Czh>MXm!fdOIqc~j%5A2Jzl9baTA|T z<&Q`uSq2E+V5vE6m!!AnZdU8Z(<2mtBHdoiPaCa!xiplrlEwNM-o_Yb{oSo_^TO_~ zzOUaq+T0`yGTmSJ>b`p|(GZxRNfWR8M%HPvV}&f=Qna0+(cFsGg>^Ge`;T2nV6J!k1p?~ zsyDx*(rm&$zDQvD{88wTgMPHN)%T$oX;0Ck31+ftUYjI1TYogE)T`y)%MR=@pZZ-l zMDgBww|c>HVb?+1YYyLAUf=N@n_b*lmbI{p=EN+WPoMSfbxt zaF)M&6MkBKgi87c4Ig(V#B3|Kp-+5k{$9rsg>5Sdd zy5C>(i=5~E+!aI0y4KZo9K1AcF237)@9A?->v}(5v~_lgK0T$kr{1FSUAL{xR)r8> zo;>HRp)MaqwoY3}a~bdoh74Q%O1x^*dsI@9Cu2p-JWKAnOqF4$%5}$d&7O6xWL*^_ z#g+Q)3RC+}ahn5e*&i6Kx3ioH2ot2a!gyVV{e9vE+O%r}DU5UH{cOrZx(C$a2FJ9lc0 z^ajo|^&2>87A5b5H}PNFc0+b|e(3?E()KsvR$*-D7t74&BwAGS+I*9{&C}{ zs~rEpyU9>1TaoF47h-R@)F)4SaZC;Chi9_dDx8TrviU;RX9s38KF-g7X3v#oey5h7 zHl6Vkw&rfiGN79gX6+8iRXuf8#wy`ti_4Z*%;UV>K|OH+(g#k_cCS0{BH21Ea;N2m z&jvwZ6+VsC8C@>hH_SQc%6@!x#DQ~Xu)}vPk2mS}ll^169U4_@18%-#-w|Wr8{b;y z(sIyVT4l#)zsvrS3!LBe6pP-hPrmCjDd}=U(LXH5zS4GG_d(fglgtL=txhGM&Fgm- zhwNYwUdehr>$-p(zjbuY*vpuKit1Sx@6Yc{soL}B)~BexIjQ6}DeLNSJ?7E+k@O(3 zRo(|a#kky3@VYyeuDK+nRDCNXBI>z=MSyE)U=7u_P90%`!z1ZY{>q=4SK)?aE^L6%#lgY93QD?S4tx%W}4bgSpBbQ>oB2e>2q4AAEHRI78o%x!L zK1J8&HasfSoa0DrOK&c&sXS`2c*K3~`D3Ztx;GBf-(LE%9R4E}=_IId_)or*b;+$M zX?xr6Dz>@L@6Pw$THveG3tx0UoUi(ki7({Msg#r?g>04gNAEs2=4rOE+_CMhQozT= zVI^DFZ{I~#dc42Zo=f;`m)pJjPt+WX#zTt@{+#vubxxEn#@yK2P`gXJ@A>2D-%L}T zOrEmkDV5IcpPfr;M>|jD6s12*FG$Zwf0h2^^aJ)Y8?S8Cdq%A$pS^7`xM=^F^F1TK zV>ww~_Z8$HCA_i=zq96;?>YHryu$Ci55yWjHaVF$;a9fhx#r=PV-EL!KIA@;qk2Rz zYrS=-koKz(Av`t$8TZ(Lc?ptP5_MIZNGIUm;t zpW9Acs;}Z~ea&QIJ$!yL$Eq-c zpJA41C4;eCdXLJ*MfIt@?eiu(#y$>nq&ku8>#sQ9Uti+!Tc{&>>Sv_~Gk*T=e-Y8ZuthmWrJi3}4-mXmFMdhp&x$*q$0W~J&a(DtDC0Xtt({Ujl?m6Lcdv`M`+)gVScR_r@jlvjOi!;gKl)Bl z;%M1v>ow#qeAAyY@9jzJsLn7PtzLEJvx7*oUc@%`}I0}VTsq%fbcS_az3!KU`n%}xHLLCpI&y|v z91nlPRs1L0sbO3+E2lLj`JHQ9VMV4$gw@8U+^2*#)!6JS$@ElmJ#TT*@=LMb)>yT} z{Hyf4N?M~zUd{Fguid);OW01mwul55kuz%)_vB=m9jRh|7}#P9d$M@^`w3l`?XDH67-&ozNOwFS@|^a-HI>bKfSX*d|bzI_v80kR-w~z*BK@2 zXd_kroRq!1^ft#VPv(BZ)j5x~gWhNR?;TE#O5VmYwYu6f>Ik*P_YlpyTQ*1@>G?E} zT}2V$dX!6F{6fBj2ep-9rKjNgL3fS)*O|IY?>u2yJJ7d6SGd&kegB*0_5jZ4 zTT+{a-|$>~cjf&9Rmt!%Ej`h`&ka9S{l=vVYf{}T77iNC?$`2sCn>${{T6Zk=&q;h zhIXjf?ci1z4e_NR57I0~J>fDQWWj&?APE!pzdpzV#u_rVr>rfy8tukx=RQ|``26Db z#lA-xYz=!vwYC4ZIp;C^nT6%rrKxF#u`%bhC>>+vY?R&9zRbTDWcg;Dw zX!rHHDEYhTJ0HHiw(aQlGBX=be*a$|9Ug6AkWaoj|K+9_|Fqa!88$!t&E~fp-WjWJ zZK?kEW_?;<&7WD1ui4&zv~TAcL+;Y&T|JeXo=xOFyzH{inI4{=4962ZCD(J#RbI_| z{?4W79+&@)^o&&Pdj)TwllxhnsRofpL)UH zsI7;^Kbxw|Z@Xq2RT}E_GHuBpsqmN5?DM{tSD3qfmoT$4%&6h;;b;4n!fs7myaUCV9elXA84$+k!95y7Az5`Tx1T z{+G9}GmR3JEXXwcZUS*FK3=<-q4?)UufoyjD$ z#l7k8p7THF{LlaV-~W5>G?6@1y=2)6S^wVUm%p&=y8n6S&G%k@&d&YEl0RQ_@cpY6 z{rQS>M8-tq(5~fCh`nxIBJyiEm9GFXzeo@C73eJJ0~I1U=+R1%T4*GUZJWr;(?tBU zu>rF|49o=`U?ErmR)b!!5nKwc1P8#|!QX*fz-{28;9hV)_&oR$_$qi9d=oqho&etk z&ww9*=fR8Mm*BVH58zMWFJR^zk#oR>UcR8EgZ?U>v*)+zF0@?}49#KY>t8WDeL4(%@_0Rj|B87Sf3Os61aAR91vBU356lIf zU@=$$&IfD2Mz9%d1DAp!a0N(!{orljKJX*(JMb6an;@^2 z2iJh3;3jY@_z1WQd=`8gJOh3Reg<9!e*h;zXg+0tg`fv)1$#gi90oUoW8mZ9)8Iky zB=|S*Gw@p=9U|3WCTIaGKrh$^E(LLr1qZ-ka0J`{-UB`WJ_bGoz5pHt&w%H_i{SS_ zI_XQ$1Uf($SOU%mYrutI0PFylfjHO)(jX760oQ?B!3V)VfP2B`z*oRGz|-It;AQX{ z2rm$61fAequoi3v7lX^dFi3+OxE9<9-U*I@dO~glbfeJ3;x&<0Lr}{?&;=HO#h@Fo zJP6B%ECtKJa-i$Px!_G;B{(1Gnz0J31{Z)ggEe3+SPwRWi$EXP1U7?yFaWlItza9t z7;FbSz#!NOQXmfwfP>%=I1H`d3-xO%Z3Cz zIZJ@$yO1-zEx!t$f5P%-FXfAiXw2g;LddkU@@?=%`K9noQ_=XYfajm>2Z$|K`$Xem zX|i&SM{P7#y<$N5{RoxUxV2ttqj~hw_?1^bF^^Z97LV7utG(7uFSS=*?UmQzti0Oj zc+e{bbX=$(<#l{0ujS}C(Kyw=^6H=E%kpFJ+Gje3^tuu#ul}#{c+H#k_-o;_9)B}@ z#^aBb@pr z)iLx1pkwSAp!4`qk3J36IepZlpMx&ouiB#_OPAWQxsZ}|>@MVQ*rOvJO?Wg3?ec1; z{re@Gj>^N9cFJQ=T_<)~I>*N25OD=*2fxokD~VLoRh~RVjvtW@6PL=v)ac(W?UMhn zbgulw(#7&qXq}fY%8K*1q@(2cC3HIJ_dsW`GO3>#Qe)*aX=zP2difg3@t>q;u~NOy z(t2yxah={n?1p50m0_Xg6lz5H{?cP;5T5|Lw;&XR9h+T>C88q#MI&u1*Hl_#Oi zUj3S>!Qb0-KyI_NLOx)rk=re;k~=Jo$VV*YEM%!)K4xj9+-d0w`K+bq%2%N=FTR)r z<^4A8ws(y7{4wbkPv7d%HjlP@bgoC|d33%{qQME&yycQ7Z6v_ zQn#NM&=cDK3)ppj1zqUr7kcAhAw8k`h3rVG@AC9rUL0M_GcCW19@g@^C{N4R@vZe# z`Q4se>#6cjcvRz4dyTJ)cGh}#F}qG!dY=4?M>Xy)cFX52ohC0q7kTZwh>{9gq4v+ARNM)Uz{YkIC0qsrr^A^2U(o^-z(buDYA3k)wnyO!qz6Je9(Ca!j zRX>P+5&FB(&pm}cfqo_WPobZ83Vi|nM)b$g&p(C!M)W(;>!tl`{1f%Ng7h);dpv!I zr&l|@E_aC>_w=2lwf&0vJ)Zs`D@Df8_W1x%J|#M_>aSD8TWbgVW^Mv z`vC20WAo@DkFNFTB_2(C^li{8qSQQh&@dN4qvuBFM(d;gv51fLp^eAWCbL@xjQE?( zkWychd5hA((3m69ZEeiowsWv@rpbU~{A%f@Yl>-~o31UU18zD}Ob4UAZANRlCF2!B{NtlE$i!y z&z8-zDZbR_V8pTY)4I7m!?PDUri9hC@Wk)Ni;Tf)>%1gF+XO5hLN=++vH7fgudj2_ zceCdsN==Jx-Cic6#{4nvk!cKL>YRSj(zNWQ$Qk~UjTu=d(;WuLkxXm}>&y%%2)7t6 z%&HfXR?|#-w6HH^Vt!(*v7XiUMJ3-_>k0Y5Y2@2aBfsP{^0%Bu9zTtI@9X4l|6hf? zh6rb~x@02L;Hug6f)b5f$umz4R zwAI+m_w-Tpm!W5*#_I8--Y44))z83Yr?nZ1%*11{AFro8oeA3`)9pK;vh1Kbpb9WEoeSmevt*zve#heXy+w8OWM ztM@3jKI@Hj6Peao%P7|4`;%m<<()@aUO(Q||MSR7 z5ytfVQkj1|h5wUf{)_GAXQL{{Ta;CmWZLd-Y&9iWT}f77Ces+T{~M9DLRrI|R!(J2 zCd8VwSt3q~_H!lGuEdvORz_oOtPjJiSFGI5FxI-pr(_zfrR}FaoAGJeU`Y*r+_u)3 z=ONeiayI2$9jm4OVbg3DNF5=oy^gOgY;0fphVj{A+M-M4>Wdp?$6Au}cjbb|4n=6g8cw>-ndtYj3Hp3(M-da8g}2mesY!)^%B_uG){Fx(m?F9k?8w`p-7`0r#i~Cjdx+M<95O#7t?2@!Inl*PWQ;7?|s;6n@-reV@1my zJ%z3~-}0VL=UYmQQ%!_L-CHN=T8Ounesy=P8_-S6fqkVpp!(6b@63U-oXH94w7&xJx}Y|T3P(l4T+%#sV_pp#5giBF%* zM0zzkWFdT2ht3OeItdj$cYMF(p{lv6LsnKz(ms-j^f0T#!A#_Q8*zQOT2?#}DaGKX zE2)vI@0slV?xK8UC|b(n)>Oyq3uSfexFr{vO})ZCZCf9at_&?J=HZm)`d|LJHMGu~ zc?0FgH^6RxJ=}KJy z%C6~C(y=M&t|{sBrli+QNnbQ2ed(067Oith*A~6>*=IjCN$4TyUg%NiDD+ln26{6z z3%wmW1|5T{551J?TBmcoNMY@Mp|l%L&-(6a;HET>efG0@*N2|3)W>wZs9xjJ`K&(m za`Tt-QO*Uktc{)!)K2X+hx%4u`o=?jsa&c0P^xuTs(YEzdZ7E8mRWojRC)RHr~1)Ye`d@@%^Wi$EpseF7molJ=75Qh&GzK%W$IF7xPe zkFJo=hAle>+IRK#@7%CMOrJOeZ; zDTZDW^vJR)Cae0hxqaQ)v1Dc}mChEr$KwYI@$^;QJ9~F|@v;Heh^Ltt9cRo-w|Uunq~-LM z+uP%X0*%soCX`Gjlz)PwXr`^2XLX#}e^EQum?PchKv6_sG=Vex1oc zJQLrilW*EU@1=YCw(J<}-NI%leyxPGzrk=?taDkSZcV&_w5<`3~XJ$Vb4JCmYu!*5-AgH*|2NF zcBwCuY~8Z%qTVeVH%t<4+pxWF>-xTRa=qD^$tCmI^nqj|Hj*7>(XhKfY%G^$z>c0D ztFG!B9ZRQ1QiWK4d@Py6D#H*PA7Ql( z!k)7Z6(j_6fU~F`A;ix_jY}wzWGzm`)2VBcGLu9qmrRtl@*SKk#`98HTm~hW9J85& z?A!5lUcwBTgi6*P?jv%}QBujxoHMnIFle?4EA(Y)o>VNsU;qTCzO^%CsWqI@ds~!VARmHcJ(nK4wMVdYflr zYFp2!a5;NUsY~T;=j}+Qi9kK$BJb|iJh+5X`Tls`>)${szk?1(4=HeZ zVm!dZ5D!I3q&%ffB0+Z}lyI6uQSnS6PI?T`UZdVQTKuE&REE1Q@_|u1J^Z6thP2g+;rebr9L-V|Ng@M6fIcDy6c|= z$1}D{fdh8IsIX+~UI|(zFK3x|nTk!$TYFBL#r2CM=G<>?G8Hw_US!q=RPuH6Zu0}= zn|<=4nRZ+{%>AUAeewlkE^p%dU&Wk7=U?EHM@-crpTT7H&~CZN8u4>7{B3jjo&NjH zgHwF%QT&}!aep_-<*I=xNTTZ7)t(p$CO_+VKh zb9~=3C(ILgSas4&uU(YV-#OIqlQ(Ys!lg!kmQW*e&6lxQ#M3&7m3r$n-$f#;%`K44 z67;K^hg?Uz;zt#7zHA;>n_8DdRTwN4w_2*!EFUdG;ONv+DJ+itt<$1?>!j=5aI8T`eRQHlWX1QA(pK2|Cr+%tN}SM{9fTzus~ zFlc7hrms4*D!tk7`-*Aam@|GKonbPoS8rC{dBB*l)vKLd2LmSHq3k zjS}~Brxq8pgN-eXt&MGs?TvFA=eZ)MaY5rkw}37+Z=bb>62eYI?fnhsH3S;AH&jk& z_LpmRps|L*hF%O6gAG-#sG`9+vvAv~EH9oAnugU4e$S^@OrXIxSy0iSR?|zu1Rp() zBzS#wgfA-M*n9AZ1MfS6&Iilq5w-9i5g%WK9K&DBbw~Yo&S^C#&Nk*J;1zIpvoX(t zJ7dN?2%ZHmf!kY*xvzy6Wo8k%PPBBJ=QJhfkh-H)KUer>nORFo9dFgoB7s@U;GeX7 zaMp787pzqURx3!oW>Zz9&LwrMO?|xy?!GqTb872vkMZ4^zwI|4^*_>PP`unWcwMEK zBFsN^I@j>)=?VF_=TaGDuevgGY##b~xDT9%m#5~f#DgO*&GVVp=8=28k-PZ; zixXUn_JR3Y(o^%-o0sPsb7Ke92KRvz;MorS1`_({ z;1zJ|Vrl_SfFFZb!Le>+{KiGUbLge-D)mzOYoPCF^?l_E5c9k5KYQTy{~YkozAM%L zccAY)bKoc+e)OHFe#_F2v%ZMyTi<1ynEU(UJ9+0Dgb#`P8znxt+20C;&!Q~kTCVN8EAASbB{)Q$1ujT3QmIPkQvcHqUkH)S4PvZXoyTg=@ diff --git a/androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class b/androidgcs/bin/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.class deleted file mode 100644 index 306bc08c9eca5d510d01792bc7011e1ef8b75cc0..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 3092 zcmb_e`*Raj6#i~rn}%%(EhN+wXrJyJ1yVD^C9E%I!J3anCXB^P5es8!I)lWI66^)o8k=tsx?i_5Jhr zc*b<|bB1HS)LS67YB$!Kj=;cj>9(<9aMxz3JjLoVbxOI%@@2a;>4z{y5*h`7|OoVYh+O%QfO4o1j5*Ch0D)`*TCBm{Prth#w+{mzPMUz4Q}=r1)YMs3lsE&1**M%*=vBu|$9 zYh7h6SW1<;Kq^}-j&#+FqA)8ieR@?n7aES`S`8LW6uG8q*jY=oaf(%es6@I%dfSVn zv(Q+tv!0P`aipl>G_}#;{`_XeZ2H)iKp&6In|0H+DvOqRPau;W2@341?;6!1H>Whr zkixb|{N33VN6J?^43~`ijdhnLHSRbGOygZCg0p^-l);=pddu-PcmlIHC*5^vUC=R) zi>!`gy4|2`jgI~{7&0&8&dU~fA^6nDqJ+7m<2{rF5`>wzjSb7a@6n=mujsgn1#fr3 zs8-oAlpXmbqm*)})}&0flJTnR%KFMSlKFJE(pC-y^me5@*8&6H459>gn%cgkt~u4o zsN|y)Jc2TRcU1U$NTVxH?npcCl?Eg{%SI6h5F{0&o z)7oUjU6!MozHHXm;@*f+O-pX{HNz>ZwPKaih52$ZQEsf;74w26htcrAd@hd4su8GI zXAc)@hU1uyhOY$d8UNr%n&HH-CHi_6zqye44o@=*z{PVb@Z)f1tb+>EBaciuR|=k1?2wKSO3I z9Pu`X%G~ws*J($6dq3@%Zy%(s`Sx&`7>9GCkCFXdrIF)ripc>PL}+D@W+M!tihUSW zdnzG};RxTDn*2gAT_M}aPkWw8%WL-J{=nhP_|W)odB7G3$edhaUdQ*KWAsF1T<27Y^XU0o+Nv?Zd4QAwryFc*e`}`OMFV zTp4=A{Sa@|i&K7#e&v@{Z@onC<2@x4Ui!%(Ueb>jqQ^Ua`W!ZXyr0Oad%yoA7YEc!`3B%a2k(zzCHOvVOdxy(=tOD!z7 zU<}4O;rmqXb1Yv0yKzp1y67DZ?w=0$PWyZlnELokolRpEYl_Jx_d0zSF@PHi|BQDs zxMC_`H-&X_Dw9hoPNk|+iqifgc5Pcixi_|o2`T>*>2q__UKP+xYK}bymQlwB0tt@eL?4@j#dM$gCw5Rfy zxTF$Dh%-M5F?QTUl~BZGXLo1jy?Hb9`_K2E0A9f=Aj8m<;h7}^?gwHhmF4(eD1~?C zM%Kr{Id@ejl#_^u1!NgEQ?KO&fpz36F&65IA^%4BLcL|sT87P#?MjcApy8g59P$k1 zzVP|+=wiUbQ)e*b43)lgouTc7B7UczS@lIk46XkERn%rEO1~R&M-k$7tAAUZjI7Sc z_lCS}*l`)_I#yBEt~Ia{NQ90pY%{DzTy>?dxUX!%CscQDa+z2K}?} zy*QwA)$?MWo-t<{)3+7-+66pesNYsFp$2kgy}JzPCsx=OQ9@F{Q-;^e^rh{-n|kCq zf#P8aHPqvtK4+*d^tv+B zjrJPI(2e$v&H}wGvW#rbyg~6>;x5q{yMZEB=+tKcWbf09HUnik7hFe?wHc=!v|;~%JfBGhLe4)&*LEU8rl#kHy a5-nn^QJw*l1Z+_Sd)Oy-h6BRN;P5Y5N$Z;c diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$attr.class b/androidgcs/bin/org/openpilot/androidgcs/R$attr.class deleted file mode 100644 index f69a8e17560897ad1adaae18fd15a3f75ac850a4..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 358 zcmaiwPfG(a5XIlL`$yN+*6KwsB6v^_2G2?_g@UjsROvmt8`hLHDcRKTsA1!MGu0k9OlKHP>NSvbYLNg#6AJ{Bb5Pbt2CkTT036(JxV&TPFV?$y>LNq}`Yxa%}EUvp`Z%<2qla+~uKfoVl zoI5FOjLn<8*|%?I-sji*2Y@s5LX-#x*3BZjlxC^4^^q`BXVr9;q|x{&vD&&26+(L< zo+ap9r1F@=E|(iJs@m7Yz`q7s@DqNhlxp zCxpttPGucsv>I4PgU}i&Bd@c^Sh_nAYf0#gY$EhTIF<8Nv*PC}B^-|a+y0zTzqOf5 z0mR{7!2kdN diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$drawable.class b/androidgcs/bin/org/openpilot/androidgcs/R$drawable.class deleted file mode 100644 index 43d486e461eb753c8772c3c239c81b3a83a13216..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 418 zcma)2O-sW-5Pg%jNsXzk^|M}8upSJa6)ypyP!y`f z20aR1-pm_j-n^O5ulElC=hzS65e|(lVzZQbsY+AFLg&_~yvV9}c9dK3Eas&Q&?XEP z;z`7%&_#SZU&yQ`v{hy_fhL4rVsuptU8ka4$<~Vp5d2G}ReeQhos3g%PfRXDw9t#N zhLF&oDlKnTk8^47-5$blYBEu#!YapqitYMARfOZ|KdfF5!aK9FnY>m`(4U<---KwQ zwX{hos!CP?b_oZ6%MrT2xAUXeKR=8xLI*y_fSHFbXXNf+T<1#MaG-PghUm3v*Bb5Pib|rwD@hfzTN()WVCk#^w?e5~2wj`n_X=OO{=-x2Li4H(8lj_yhb= z#<|17#@M{cd;8|?%zS>me*iegAVh_5VBIXTOKFx$TOSECbyiJhX%>x-w0O3;4^bs_ z=HgLAT9{dMo6KeE3Dt#AhCo9?E4C){!uW~MxeQ(cfJIvx6K9_?=?aku^-E=xzaj+3 zClk(y?Nl}ppxwjG$;Z(tY#HxQ#8R2mB@AMah#+}Vw zDz8-$S0A4hs}Pz)W2B3<$TFFQ*e4AB4&%PnG5BsgJKwK@K5D2l3rn`feEk=1@Cy|? tF}Bzdl^m#@zG3sVZ0Rr-0YDF1jD?jA=wh2|1v@3~Vvp-8uE(GBzX5PkVHf}a diff --git a/androidgcs/bin/org/openpilot/androidgcs/R$string.class b/androidgcs/bin/org/openpilot/androidgcs/R$string.class deleted file mode 100644 index d473cb81c8c6db44be5035f5848de2cfe8504c66..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 445 zcmaiwy-or_6ot=)g+&BG`~@qc1zNbV*4U7kkPuDK(3)YHEJKEw&CFu!Gg+Bf_y9hX z@$O<_V{FdNH*@c~Kc8Rk9{?`V3sE8*TbD#Ol_pi%W|1&6XVol;eKbDxnNubS5fIu7 z@hl=OOcLEs7c$NWHIb%IMl2MXk$0=*RJuno)$H3D*;wd_a4P4Y#~_<4PdFL9d9xD|%C^A%sO3SgGdiTks_zeO>@9G{XprRHgYIaOv)g&O0kk^hq#v3*V9-6I3;+NC diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVDataObject.class deleted file mode 100644 index 95af7d70364676903cbaee10411198d19f52394b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1127 zcma)6UvCmY5dRH5pqx~cTC`SeYc(ECyLY?3*$?!sgtRH;fJl6cMUw++nG)jFPb-tX|-Y8@Nbv)=R|5X_(F<7fbN%xRi+1H?FWA=W2N` z|6he0P)RYfmE(^oz z_4#Sbmr+KQch9pztl&CF+=3czFqqxlMBPMj{pDw diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVMetaObject.class deleted file mode 100644 index 7234b135ec1e4b601e8d271c48caf5fa07bd47ba..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1440 zcma)6T~8B16g|@xT9yi0KvYCl5!pqc@zolQh$c-cCi0OOo~G@z3~YCr+1*Bc^!NCn zPb8Y?yFbc!XSei&v}&5n&fLBC+;h*F?XTb8egJrcViqZeRi&Fn)fRqRdMYeNyc2To zta$kR=(Py>o9d~kg;``6R>meKNeq)uq%Xs#46akIobnDYdfaaoca-u3_e%qz{ZLE4 zS#pmUGA~qJSV&_kj|ogN%vPi?_M%o*=mTE$1Vf>sYTP^GTAFh=mO~hSJb{-SBuKyZk~(nmCK= zG-Dt1rPfO4aD(B~p|3@typE{bHPs?Ncqo-`x3!|NTaRsPs@!UOvL-`2h}uF^77d`I zTBx*5h9y2Yt}O#Q^6R2OLe{tK*HIAK;(b!-eXyn9QD?&Dz6wu>SCOuXS2DhnLm$Yt!N*+?6n$Dij&^jJY0c8<02%sGbYp3A>m0eSv`@jJ)uJaT zFH05EwA)DXkjE7|8Jro+5{lVf#kDv)hXUrPkLfVq?eLb)ri1kz3-1bx=eYTkPDu~L z!gT86TRnWMhi~CFp&B+8mT@P>UxD4le@1aL8S7I|U<)y$+}uUfX$Z$cQi`kN62MTHGEKoAzkPkg7KtO-*~Z->koUv)?*s zGHk2=Pg-VJ2r=w+)IP&pv(s&7dv&$j)EIW&PRAFk=$2`lew9JW<$DZ~2C0u>HUUbe zAcb2D(aJbvIj2ra(tOvn2jy127pK@o1+$38APZwzfsCkF-Bu7ooTyaOHaer>q2V6z zL(5=DtB%gC9(PS)2b&2AV8KBY?y*K~c4c%Tm9BA^U4|hc%RjHW+oBJb|oYfGY09U4wTBTG<%eDz~6C8@S58U>)4dIU(Vi4Gx8gysb1C{7`(N4EHOzk&7B z^U?*9=ST;}QY0`kv){=joguCDBWK8H=UDkdh#9QXKN)0O!aOoq!y*mg5rbNKoTEfB zLX%wB+PJ{_1RSLRj6q7Uma!qklF&Q2JBGiYLIiyI3@iQDQsJs!5sKQ<`Xx5EKa=NL w$~7Cikr1a#e>~jfxNVCEvp8Np&J5E9&;M~G?Fz;YjAPG-z1f|;QZ!=dG&j0`b diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObject$UpdateMode.class deleted file mode 100644 index 5e520fa0eb6d9ad0cf329fa2572250588a3e365e..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1333 zcmb7D+j7!S6kVqQ0yMqRN-eF{OSM2R5w-OK(}AH;8M$@O@?7jBdJL~-T`Q-vY3eQE1FeF=cQ*O0&t8JJqNA7CJ zj%I$4tGQZb|4?r@OV##)=IEu?fiA+wFn*{VYqF_XO0l;66d@(I;7`VGrKx%#juys33MX^(;{_CYt?mSm~0 z+UnX3{e{5?I)3Hnbsk7vsz%e&oUTnDw>*42IWvsZEh;4yEK9dtZF)zpSM@bu~ z{un8UQT1ioJti;TaU*yXU6sC~6!pV95|b+nXSh2c2~Ys~Ns_x4vBX=WvwOJTPv4|c zJU!aOV*Ry{yr^fm%91dDj^)))^yO00B^$ev5F*R0_c@Xj!)t{jEO`$3JJ{dz1Uz&( UA5lY`djp$1lkyp!;8}L=7v>5tU;qFB diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObject.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObject.class deleted file mode 100644 index 5e228155303a29cd063056a485473fdd564000c7..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 2255 zcma)7+j84f6kW%5?8X*pE=`&XX_}I>veMQKv_P9Q#7R;+4w9T1 z_>|5tJo3T=x1xuNphhm`24GkU0s;aMRcmp@72&*p2M`p|R zm1_-CS$l;9{*Spz>^C)ZB2Vx9#};dkpPtyBh>m6`QpO3|?M<+a6c)%UPb|~6zNH`; zy;`iPV()0k;fz2hS*v+fQg+8J z!xEPBcz{|C>jFLT$VA&Te1cCoA$z9XlB>WYy!s0Uo}q8VIKYMP zQTP*=9zMs!UqN)>8l#g3C_aln7+3dEG8muU$E~>BaKL_)uoqZpjED6i-o`lQd2J{P zMpzJUF{=K`xXq4K7v-SyRPc5OGt@(17I!16bEK-iWsQ-2%*FNcL3EP2mjnEPa90~Y z8|cV;n+%l7O0^Q7s$z%n8|HrGOHwI4fYHJY5sVQ+`Vb9;X1Uy!)7R{#J2 diff --git a/androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class b/androidgcs/bin/org/openpilot/uavtalk/UAVObjectManager.class deleted file mode 100644 index f4a6dd7e4e5820644e459a4aa5652e5f2a69beba..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 5422 zcmcgwTU1EyNGyRCT1^jdAVY^4dKk#X zrZ=&+)q07yCf1rXTCAy>YBGdG)4FsmSAEEfk9Fyr%NHMf@v-&W=bX7P!vt2lmMd!w z=l}oxe|zt5U(P=H%ZJx*0{ATcpuwkbZ`>Yjj!#&ziAXe_Xr3~s6K3>@=H6X>hX%*2 zp+uJ%Ge<33LqMTy%$zoxqh@Th**#RaqifeAN5kDcM|O4Z-rJ*~!ra>(k4+}bSfbC2 zPFa2`(-pM112;*OP6uWx5s5Z;MkW&>g_54gXv|DZ*_OiIoa6Sq^%53`cJQAHRPr%n(k|OJPl{bSR-s(vstlBf3oAP# zF{^uOe9*Fwn1fN;TG1IFGNXN_9g(%S8Au$9(9OEeCG7N=rKzR1HA;n+onp1^HkbF9 z3DcDe)w|R<0qKaxqm~&9tw1e4tzjKeGd_ts2G(PPf)V9&n7YhF+*YWm3wtQ(c%%*q zbua2PY*JXg5Go~MpdJmRHfEhjD6Fc>w#PG3%-L+93HMQMGIENfF&<&r{*1vSyr1h) zi?=J&hGgYeNW&I|dzK(lM+;gFJRmxP1f%Nk9v$1!s-aC`eZlJ)Dn+{8z~{hxDT_?@ zL}H^+E9_+P5KXRJ;981m9iK;shFuEf4nNs(Ft8hY$o8Nc7N-&%*9YX*J_Gx4fJHGa z6>?~V4A%{0vzJk^9S03Oh)$LjUF)(^!B^NsqYAo~5e$iM-3AT`Jtf2tw_JX{VBjIJ zXmzQSh#7UlQ(qTe7HoZ=1hLmZA0DP>=J2ral$DXGBpndBeo4Opg}YKr=BJy4v0HNP ziw3?VGBu#We`;-_<|@RcmW>ib0FsDWdM z&{Vv8>7Kxq~ z9b>Siaj~&1AlW;w?+apz6((MY>~RApaFR{XoM3BbWSX+|q%P&@@ysS^WB9Uxr^NqY zBJRp-c=~q5lp#>ZX*?^&KBo|3Hsz8NDjbEZz)2JozG7eoUuEJlzubgU*l?Tfm`XZ! ze1Cj!Okv})lrga=9cCY@a?Q<8Pcji<aZ*y$YzX`jrigf%Ix zN?~1L6M4>eu)NJgcbG*{9J7u)x7;0uHZbIvP&6KMva}+fZ?>0(FRGIhsh3q(0e3&{ zTel?#uYF11MN?n;urM?G033LX@ zn_L7wlQo|dK7-`J%R9i$D}~lY+QRJ`tCx>bnQt1nh*^aP7K2y@1{2p!*o}4JWr;f# z%6zX#+n;(tlOpznyf%|N*f=?`wAgZzP6+t5flIi|4zq}AI^>v>ZX?uvXL`cP-fhj_ zU5)_?2bQCDc~C3KDCgQNIv0J%gvIMQ16OcO29|s#!}Xm019T{?;RfgBOhoqDcH9o) z_X;h&G25DqN2jgf+M)P3zdFoBBp$1su;Uz|$J=W45|J>6j>$+(5l-zou7e#@?}<;@ zL)N~CjNX;GUnuv9HmswG^2Ompg$(yxY0fIh9S-qauW;4|R`Qu20{mUcolf3T{JXkg z4rL8x`c+gk+`y{-Ijp{lHSaigs`*=i0DnvQD`*BPQI5N~W4O0bgSA`%pTgZPvfrj1 zC4josa0P4p^SH-{u32?*^E@^xyocKErg=0fysk!?c-rjaUP}^N86XmpP}oxJ@2ROh%z*2VG@utQ(Jku6v^b5U*8@Ty=gFHU(ATh>%NJiY^*edasDYumQSA`AO$|-gy zHenAo<1jyddeMvle(jjp!l7y_p5uJ^BHHmiesR2p9k_rFyu~kuw|Rq+z@M-W?{ocE zbm8yl#y>f||C>nvMVIn%Vh^HMm2vE@B7-&PSDQFmx8PB=jq47M$z2#$y_|R-!-%rD zeiCEqIHKwqj-oTDRj*)LoxySSCQhh1oKiROl=>r1tM~D=lg+P6O{iO`Z06Go_!{$h z1*KlZORS|T6~)V}06z|^E%-W512ENkd;_mA-`~Oq_$K9w=}kGlg>SP8KOi69;f_Xc z%5a7^g0$N^RR?+cT{)%QW#mOp&yb<-;|K85#x)Ld06!$xwbbfb@@m?Wv)psFo+Aom zXmsn3bFhzRz*?`IyEc3IC-umDko1@OcBARm_Y8u(Uq-KM=&#hb=p;sp5k9>@uQ<^0 zKM8(B9(;~v(goa|v)ln=`(yrfJI?D)pJ}Fq^qC^jewhzGCyAs{f%IfrNl{wWPqIMH zJ0SP-mdFP^mvV8=X5j?WI2W>T-dGmSyNlvn#80VRn&v(RU1$k5H2T*j@v~ez{*^^t z#*QF<&Y(K>J0TaME;4wzn5t$m%>NX?`~}0Fi#h9I9^_wX+dh?JA&W>DZ*Wi3O!?9l z`XIPsq0g~ZyuHLSO$GIr4i6!+ATk0zcg!CJ@-e2*%Ioy0V$Ec%Oe(LE^=;=`CUc43DoA3P(|56;6 diff --git a/androidgcs/bin/resources.ap_ b/androidgcs/bin/resources.ap_ deleted file mode 100644 index 2452fd26f12793bb5445461ce339266070961506..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 140460 zcmdqJcRber+c%D=GpSBdWRI)}kv)@0HX%DZBeG{!h=^<=BQmnGH)WKWj7Vno-aF%W zyy^43uJ84`@9TQp_dmbK<9F8CIo{{{HIMN;j^p`CLHZOnAqEx(3ZorcNjPp``sHOz z3=B^!3=9Gc3=A71TQ&I}VN$j@2l+U9op-kwWf$&exwO7=?xuMHGcT>6kv}V9O!GdEkiwp%Ny?<$?|v)hLzm7~z0dOKh#YX1 zi5!nf4th@B=qkIf8og9Q+LvGaK(c`-_L-;rQ$6E?nsI0SXSVwKN_{Kco_X>w_FuED zXnL#-Na>lZ{6 z{%sY}%T6Jju!;?^ie&%3idOn&Mh15JHdck*2Ur{aXoFo zXD)nZYWjp%<>|PB8TIInfo!B%2AL2hlT2`dl($L1r)KFH>($v_< z*6vtj!#`Vgi=zFGio1JcpBPl9~I+NgaN^QrXP_BeE!~9@)$iw(B_HD5N-7odmLEIZcVYz0)Up~8#51zUB ziGmlKZwJraGjWtCgVgk#;ORWk3pJj3qoh0MNhZ{LGxrz?NoK@jOPp)H${+VD%hQ@< zekS9U)A){dr*v=1{jI;fsUs;EMY-p1aizNHdOe$@-Y1r!u6%kygD0~W*yUuFNZjwkPrq;U(T7;_<4KkO>wtqNq2nI@9Cs zUHs+5M&hjOW*^%IeUMy-bGl2~3zxZ?Hw}IL)3>%JN^(h~AFI$RExy~n zRQ+UeCP1gm-Gk%o{jSZXnDgjn;!_$_QQ9T5B@OB6B0&|Ev|B5Ar-p-1&$G%4R<_Q5 zED<*&?dW%Ie0zWOWhq;^YphMHm;0p|o}*;Sj!mYLE$f>ZOxBq+Uw=$#ef_5DL1fAF zU3YV@lWuQ+%WPLev!*w$=1?hXvA9L=8TUcCbRyTXfw!A#<#_QT*`GtT@%z=rpLBOa zbo%D)PgR>~HRq{*Q&`KnpLpLr$3}#1B-4#3tuA_`Q};x3K}nD8-^994cf)DWTzFnM z(OfHg8v`R-Ry`YA11t=@<13)r7?_~h{_y4ua_ip*?>}$g6?y*@o*D4$g69SJtsp!} zFl;c4Fl;f{Fbv_H9)=@4^)W2qyBqMYA>3mM*Gw@CFsv{vF<9ZVC58#y|KHvBW@rTMDL|_h@Ebb}DvaCk8Ce}G_|6bMOJdx?P==mR$GB^?z>D1V&|x-2MNn2N}p02rfnjyrSS0kD>ANs9)kb8fmdWK#PH;Xr#L(x!qXC-KJdhbR!;N*dH;_D zVqlyOYqKORp1dW-$9 zcmJ_YuwJK-um9(ElKyq~|E?Wmod0t>EB|9V$o!DGBKw654*C4g18H9iKK%1Nvd2{a zT>Nidk##(g+2hw!$o#0 zH~;jBT>D?m^PlhkPy77a7x@u9ka;3~!7Dku9Q`9l$alz|A&-Cd?Vs=d-*R;FyZ`zx z(l+9w;Pn!6?ce>K!QI~lxCIy($dd%FB6#1>M$b`C-@@p|W5cJWY^DZQmaI=LO#&3; zB+uiL;KGm2OWhM!g5~i+o+xBMyK+YY$Tmxf-+tiqYhlRIPHWR^`>5ls@EgVGAC@@uo(eW149){cf(}I5ngqovFwx#5-ysmwG z{elE_y1bctsbKQDdWli%^(eYmw-&e0_?;iR+f}qZA0KZ~AYQRv?s#jPbHwJA0%Pja z$7W_WQf5&R%uLh!wKgJa%K^xSdCqXt%=)B`Q|@kWA1$|&lar_X=4CgaKc}axtQ?gZ zcP%HPNG9yLIU)q2@$2_pw7ZtC9jHl4O6s-|)}^JTyxufw&f1l`_HM_>4n?*%MRNR|4AFds|O4a0ZMDAs$ zb7!6vfNO8@)sbs9*A7Ix)acZCb&s#U-w!*K?Yao<%8833?H1hMOGuTxM)x!rx&BDw zmDFB9Dy6-h-AZi$vF@Z)cIKZ5gH4a^_}cc!kD&KW1i{1`iMHrp2rymoW6K z#k+1mw*st_9&S=0p0H9CDoO%Ih|*!yeR!z!XE)fPlhw=zZfySUI*;Q))lB7zT=YjJ zuL~_o!o5UVYpiAH1h(f#)U(ot=aGx}vq$$Trp2UxH_BW+pg3ub=2!GL$I^2)w`qN* zr&ENP(~dVmH1(WRMRiKbcxkjYs$-e{7i;s~T%-x~WeK_)dsRb{B8BJ#k8h*&`EiWM z_u_H1VH(2oe7-A%QIV6)Be&*+{Qc^f#7fW*&PS ziMZMMtbCn7dc?Rnf9LJ;b9_W_aHak<9m7L?4I@d(ukN$;v_8zuh~i`D51$!YmOuCV z#>BBrxw-s&$;3yDnv09eNQysK-h-7I`4ts6Hr=Fyo!v&YE{4@RJmjaMTI_F^Jt-qZ zdoLb;+<(XQ%GHj}?rJ z-rLyNM8wCt^^0^bZ_n?nj?XPE^>(I6{umm{Az+YWM5EBW7^1ML2L9k+Q6X(@GVO6Z z^6OLW%C~QS4%(MX>_{IT)*%;mdsykP*yVNV4Dns;<8_Z=^7Zwt*qw?~(bgv4GFWw~ z{#9ra;;=NBIaKLrZf6%kfPK6c>^}+$3hcUNc`|Eibo}(h2Ul^P-zFDyQV?)l>M40L zaEqP&lhmo>CdLv1z)kbg@p&Mu9Xf8KR*{K9q+$qU}R+E zdn>nb(w3H%m%sX+E)DWM87xy=TwLULUc1I{83PfI(e<`iPRZ>-+Yqt~l5JIKcV1kW zed{=^C@Fa+#Si0nV<`W4a^Vd*jlZf`s+gy-$r*h>OhVFSo>!gbIP5GL9v&WVcOr07 z6^kVUMHc-9WllM?w6uHml!r;B!!FV~dC}n)k7qg7*Y#ey*kyCB%ykGB(`CJ#XLBmf zYHbGhxCOMwR9kFHp2xxbO##^rF&P<|naw`kzO1~OmIq20{!ga{2L~z9AnDP0A3rK= zk9gFwT#?qAew6=kV%4eW>2I-DuU=)AmPQAjI-XktYkGI4B!#m$Yjhy{H(Oq^H=HKH zNDtlV^7AllAFSg+>38Im4uAOY;kx$@wv?3A8xfBh+;iuCba&V9iJc5fU~O&9ZhOe_ z>t@C0bD^-Ry}hdHIjYF^e17y=0fVYdMjX7%q=eU55!8HxpIqv<;Lg!152IoY z)g#s@v52i%f4iJfRTVFafvB+P#$ym!8yk+>T4^ALLL1-jAj@vZ9d{P{c-G=Ije$f2 zb%f3yMJod%hb3KIU8uiTa^vI4BBP=%H4rkhvi1_l3no`o@YkIfh|qw}&$HpLUnl)p zstjRDJ>Gh%wTCQMii?WS4YxF5AQbL9dhb(H(Wg(;2M@$QymgYs|EhwL(mRF(CovE> zAI#%5t;@^I3_u&d9$4%>bx|;BvNf9EzhB3{c|#)R zkHH-$t9vk~R&4g;daTUgHw?tKc$!AV#bp&0-SYOQQq#7Nq;Q#`rek3EJC+z>8KPG* zMn*C)%B`5Y{&$U(TPJNYVLPd4cGJEXc70IE z+W3*@uEHJn>SS*|^<-pb!meTCof>8XaTT zzO@G{HWR>*@W_DbSXiH0I~_if>v1;aT1Z!5 zsi8ru4_R41dVACA>cr|!1TEpJUovc?w?C(;sp;NUX>HEkz$>tFi0fMYkd!0}iiwT? zB3m_UspgO6(6j9!nX9Lf(NIy`)FuqPa-)kjMDQJK^gr#bFk;d&d!4oZ&PgCURRBIR)#)_U?#*ravYwtRXHe>{4-Yar5{p>>l!6 z=XC)AP1rzeufV97m<+3D^O_Y?Z_Gh65GjA$Fhj*UpVng7g;+AzYja|u736Qqx*(NMy7BL+~D6Grx{x4FErv<&G*kVC>_`= z&U+?XI^;mwcjb5-p+U3nVpv3{U}ps~|rot?`QoW{-~ zhUR4Op{ZqM55WdgvFC(^hi`trb8)tXIq%xZSZMBoW2Am05z}t`Y&B4~C%Sgu2rM8L z=JDhT^Z4mKZhU!pZ;Gdu3DoFBVB4_c+S6XX#Pt>xhn-Z?)Qo!> z7zpZ#tn93+x;j(VkNaqU;>^rUm!01)>>Dqu{oR!AfZ2Ec;#UIin)haRM%Qf6)qFgb zW=}DHr=mxnv4qx|Xz$C*Gn`B`P08K8MoCEtg@vC30{!I4lMk7h)PJwxrabq*a`x=m zilf6n_Vwp^n%MD9Rsd;BpV-f`YE@#$6vg#eH*@|#lAdQZpvGH8~R|<#*2~NJI0xe%{G%lQF*4=$sv(w1dV!=&-LVBWd z2M-z<9Zi5e_AOFPC-Vh`%f062<`Y5jmj_!E6h>tU!uTO4=M~%CW6fJdHqH@Dip$F9 zGsPDD94C`$xLD8rQ{nV?*O0U_aH$)J?1TEAC{li2M#jB>fBe^g&z zUwS~mSsW~{i-(tSeIwq!&54L0#CnPL)0?T7&sA1b3_Uy;Inqu^N%6rtUL7qN>p&SV zQBiGe?O*u@F94$^fByVg{=fvVBY3aWu`&J2moLLy#bLG4^%)fv8lW9}{T=RUOG}nm znEIZbKYtR_oW>B%-bGwPK>>%iKYDz8+y!iEPiJTH>guZW-cme7nxf99u&y z;a;mNFSHr)Yhd8-a;a;vMklzfNyW;rM229)aP~Tm_T|sx;mP!O$jHj7z%osBB<5vj zvxr>?-`a8z+U!wY`*YxfDb8eTX}NR}iVJ9I@ZDTi!-C!@&f1Z@=>%7~+Wkp3Hs=Q` z-A>gy2qg5_AE*2=Fp#ys?^Zr!DVC^*gM$OA-Z@(nE8`}dc(_V=q$ngL#JMGKC;7FDi%XH^5WlR9Oh!hAzxkunU{kqxc$kUt z=0-n1$3ET|R0yo(4fO&as=AqJk)v{lfb)121frrcQ&Pl4M0Dz!@V{!Ep8Eaz$Ru+wH{W+)mwNbGDZRW3{HTVJ?v z!R%mf6W3Sl`i&ct>XDpDpzvTmka(?1hs_HE->=pi!!t%vO-&M|S70?#lfkD7B0!|; zrYLf_8e(F{(Bq^ENEq+|NHzL2S`UHz4TyIUSgs1kPh>~=itPblq)Y4|Qu!*x!SN1c z3WlmI>EkzF_gWA(%rgPY3$Bfu_-qV+yHuN&JtI7n=o z^ExiYBRd2-3}$nEq0Tf4R2WRw;z+IT^tZRPXsRG&;Nn7H4Q1$q-c{q(uz}bV_vv(x z94?M~GkE7eTZ_t!gfxVY{B8m&^mhSC5`J-!vKJ6qTXinv4ta*1?sy#Z zdF15gvdV4Ts@$8)+8lj;5ny=$yXVy}$9*DmW@2K(#y>sZm)8ejxBk{9#DJ#bUtaOM zZehfGBQ1jr6a8M>?m5i1dl`K^XJbu?$0kk z;6K$K7YSiQP!OKn{w)CIW~Qd0ee*_rYA1J^TUhjfsDbc-z`7sI>wayo$Xi{te)6kG z>du`zYfgfItF^GZKN)hEZY}f!?CM<_sx&Zrb{!qM%tr%>w8CG%G{jKhFfp9xpCJ^6 zkbEzzc8?i=SYY5I5-x6TGX$@Ji^O|Ga=bhmCn!TtTP-GAvy{~`ebc#G2a=8%wY9nc zG9dyvr%!T?p5E-UHx3vmWnEoLuVYa^)VzDw_X?Yi3|en3Ze*W+iSqg|*rr#cJZ8Pw z>M*vccQL1-ahN@fdTwrRtdsB)p+O5H29?=O?OSf&5`?lK1A=bYWpUr@PMkv|V628p zo~WL^$Zgj~Xywx>o64aRy-Y&;b=N%mgZfQdV$uJO@?b_1)bX62OgO*=#F>?q#jtxa z)kP>`h(3UvMAvzqL6FR~FQis8Kl2T+SMk9g{3>}8=i=%*x$0zCI&jwLCEr`Q_Cyg~ za3+wFp+DX`f5~%KSQPB-xo-P3cgu_1$m^3vC%yx_Ny=>jfpGyuD=5R4u`=|4RIUpN zX}fMOy=on@^kQ-q!NFip7elW~s=^ z%5vb{Idg%G3Yq69L2TQl4l6OdvaMg{k%@`&XgxHp??#WZeDm}={ujEL<>kJ;&G|?$ zkPt^nl&8PeBL>;Ke*Jn^f{<&O1Q==0ZFQxWk++u3?`!ToQ&(=i#rIJ+St=pYccyx_ z67d~{{UH3{DmGvb&<#e&xQflA!Bjuc(a8l94&wr>2EoC1&@H>I1$8V;1S1S{#Z9o7 zskGEtF_-Vg6&O8eX4f>5y%CvZ_FiV|+V0*q6JZP$vv?##G1|_Pk=Xe3aokUoOiUPV z%XoQtVHTH`wpx~EfjD&5F-5@mch{%Qot$F6rhv#&)x<0`+jQu>FM2-`owa7He#usN z`11Kei&!ojm0^}UVasj8OoUW|;=YiCL2#dV%>Lnat(u32$ZeTWQK}>%*R71gLS^ti z5Oex)sPL2<7a~a?Ff3pI*B;}-+BR^TS4cL$8c{HtC$O35h;E)b96WlZSJIp?km|EG ze>t8w)N1ARwO(SHf*g(F`^UlO=@U3X$kW^X=;>1h&{+s_gRaQs!|Jyu2x)?t{n**z zMbwVUftWrpzEO?IepQ2xYmgZ_^J{kN6!~gs+pOMm-K6spjzn;)NSAb(|2;5Y8s#>0 zARn;AJ;TFt=8X4T)RU_!utqm*#VWjq z^?cn7;x9T(r;*Is*8F38ig&=Oye7^hGowzW{ccAi4%={}ww?Ymn%JnN!+ z>}FP0CelY&*>BxS1s?>#cUPB^#JTi2olawA@Qqkro)^gZ#i>NIFV}r~SnFo8)v8^n zk*QY1lx!E9-Rv9I{BCsTsxOv>P!RDBduz6eQunj_>icD6<*zu@(@jkHrS+Fw=P!n@ zO$yWpr}~qDEl=U#pjRxnv^_#Jv#)YnE;y>`wJ!A zYZDbjse|4#r6hmy`4Upabo8_|o=&YfK}i1W`##3}C04#QqL#65p<>C~5<+6x9-R0T!(rN zhFfU8jT3j3rTeNqNH_>5fTRyaMGxr10~FFkA(;&RApPLawz;99k0=bOm}rucKYR5Q zTXWb0DruW!Lt>6fV;Gm(*@XGY-10kH3ofyjx-R3&F!BmFMS3>5+E#Ex@=ja6zp?8P zso;>)cJ}ITrc`>6=wgs)8Yae(*n@?8FF(czxt0L@1U)ZsTtDDY^xd4KDy?9gLes-mFZ-hRR7!N*s|Des48=-|OxVs&16+FqMZr)j{T9*T( z>5U3UGC2H>!J7@gui*OHt&H9V>?jK`^}ehuT?CVYmR2^n9z>c52v|ZeeA%}So%X)m za#*>H^Yx5jM*>5=#lZrpj_W&%*~>OpbTb<&xRAc+m~{R0lpgH|5gKB0r1{a^ln>b4 zX0&hKo?xj_GB(+8`xy6jc6ssM8x==)$u3Me#xz+SorEYhT{*NKhoE3K1O>rVG)*%z z8NGSBYq!K2&nS)3F~+A1!}ng)MSn*UIt z9+fJHSltQINpRgaG>Yy4qy(!g;IQz0YjNN#4Hi??7TX1e6FjUNOxW z30S(d6dTw#Yug7ZMen~KEUaaewz=IPcdj}j%v_dPq?R^Qy5>;M7YoV*GO>}&Y8+gw zL5C|ZM2>wue)5+uUy7{9CEf}+%29;8=&Wl!5a+~GQBz}PV32g(T2Q3=Bw^;iYF?9{ zf79|sDT@>i*fs5b;~x;J;RU_zYzVmVhIcqQV4NH`=oJQNOTK(Vf&)fvG$L4f(S8PS9iBPB=tGp3E!1V5X?+G z+(-uzrp0T>E+eJh|1LYDP}KmtEsZGUpqJRT^#h==S_Y8U52{=tV_W z7xcUfLg{E-_gJcT4Ldt!+?InGg(e*><^!K^Q>h# z=KxBV$6SEQt|&M8+z*k{9rk3?dbX|VMH|)RQj#v0iGTCSmpL)3W-CB42Ha6^j%Kmz zwxzc}$I#HwuPW!lg2F;B^IjILa=gEIabOV)xJXDED3&Tt^>dPW7e%FeTWx${H_vx$ z-NcL4E;Q_TlLh8vGPhcJE4!S7&XAEXM&Y{vW5WEEx7nr?bUcGuJ-y3Kp|zs)ad8TV z8y988DlWC;h2JPtJ@k4$oo7FaRr7#7)~-+6u^FlY5;0Z#YppWTfl4}gYH>VPy`MgL z0^V_=)J_Bc_fbr#= z+Z*d{rKnnEE|~s$nNq|a3xldA_S=zc%%9TxCpxd z8UZqwAXbDdzB-h?(x=*fug}?>zj$%pMC8xa%GWf;>|#4ojTZYsUn+E7>lL&_sdE|# z+$Op50&JiSAxoI+)^)@)hiP1|AA@DccsHaQ89!goUoXbc+N3q1n@X*bDB@wE zMoF7SEIAYI?w89OYgHMoE(T@BO!-UT&JSuXwM4bXf4cCbn~7aGsgV3g9KG`zVt6DG zE*`VvCMp$*4s~sO=NNi(?`%^en=2(P+O{t)-Omf< zD!=E~p9TPsdv&LqSzYl3~VJ|H#$dXJ=8AC2Eqcr;M7~luz!%&@9_SKAq z=26+EllUH0^pXV@g&!ta)YBR&DkqwBuSx3%r@r&3eL;6qEx`6jD^t3b!KC>I zhd_7P$9hAj19`%=5CUvr1x?K?XdSX`NW!kZz8)K2ew*997D+eJN(MK90?pc8YH1v{ z0-4Rri`FBCNSFrM7Hvj$rsdAk3DTJ`+VtCgT=x&3lK8ddsu!5FtBCDx+VltXV>3tC`5mrTz9C=sZkb)ELg$k z3(R|2^U|=SHDQ3ob;)()%Nd4mW@8P#+Z2`7`hoi&J%swXk-r&Dd|s>^1p?xB)qspXF$$B`URUa|6f?d|QbFI^%>>mueh zVek3G z`8}!ins-HDdnFaKWP%M@dr_QgOGi;2KE+pdtN@}xW&0{+v3vOn|6DvnSy$dqA-JrskQP?PK!aAqXe}K0ZF(<7eeVk_R1}-ed1O1`5Hdojp z{{pvcUEDp|?9Mk6j1N;Id@nKs%`V}-h;@w4_!C+k~#PF*Kx>L zxoq{D^b1o`qOh?b!&$nuJdy{Ptz3&0Mgh6T>uhX&z`4>a72Qcsnupcd9F$@7#9JKw0BMz??J-nz^ zsG-0X7Z!fC{bF=-GPTgr{yMf-$W>zE?~pd6g>nsqM-u1Q#56SCfZoD5=xY<%Zi9x9 zo*?X(*_rRBTcs9m;)S;@Spfc@_^{)B$y~KHN}ZvQR)u<`%zHT5ROGa|S!@_dZEg?U zNGRY0nJsbF8pfL?N6xZai&Q8#DsXB*)?ns&qgV9okHeFZ8mL*B&^QbQ!W3X z+VW;9w0TPD=~%W{4bvNMLylH;yZ1_0gg;EA{V|lzd#$G*lKPl)aJ2(BIFTCVmXx2b z2uTxUR}MD&oc&0Iq2BTulK4j4aaV6tH7Pw*S8u+D^xV`plDS%+*ZM}4I#58sQm3?e zE`lpZ=3AX=x%rZUSbuRr8X;sRE|ZC*D2$Fd3~}%&P3EfS948jW&RItqWuJ9&o`)`S{-DpE^>b9^vaRoFBIlZ#9&Ux{;#sEzAgsVS>Hy7F?UUhs(q}%;qcX9A~R3 zQ5^PWNqKIJn{VxnQ9(hH&@X4#;m(~Z#R&6z#vFYr}D;pz##5vV+r>cOgFJJ^7}QjNbBb=l*oQ=%&5-eS89hSaF$% zh(MgU8c-bqy-`{Pp`rLl1dc{!WM>C;)^&u2h9;+`UPCgY>}c*P>3Sx@o~GcVl+8k{B^?r|j)l)qOI{qyBTI+{-PPIk!v<%Gb0g z1=M&f)4BbqC7#z>Ok}rNegh~q zs=|pOqQdnM4!2xr1(Q&z@I9|^;7}!9XUA{@_AJN2t}TT}J2#r$Ly%IT|O*2_31t9oTJ^AF?L!U#fiWNiS#d>P`Ko zlc1ok`RSe?Kk&t3Acu7cE3G|KIeo*?W82YXD%Ru{ADprY9(|HxY%#=tu^Wbw=ILj7Ut(1OI@vi+WL?4CQhp-R*_Z>JJ$aSFcWG z1pWK9(+y;sNe!}4?*WoYY7SqPXw1KI`LZcgitfwEJOHQxmcwpsLJHE&)->tgA&vgy z`*%nJ!`$AVC*?+C8#ny?8S^(1`T(RSlMr`t$ms$L2r)QyP}U6dc9$g^NNTQGEHLQ^ zZ=Rwj5HBv&bpP<_=WGUVFL-&V**sfG?C$O^c3Ra3EQ$o2P<|Nqk@LFDtjfs776SDy z;J9^uetzaG7Uze`N=@L>0&x(as-XUyypf4X>+<$`4Yn`(=*H6}ABjqxh~`ilO&2;Z zs_Qrml3Z1*l-KTlJ>`^Fxx^1n+I^w616YUV=2?)cvj^baTd#FGyg3zuB?OjB5JOGY zmV|$Bjpi|l5V0OLT&Ec9og5ZmkH-0W;;nrvJ| zWaMUmZbKt2j0&6yph2Bv1%Jq8HF&ItY?x)w-;LFdg~%2k_3q2eu*t-HNbp;{bGW#6 zV1V40L`?D@K2TIl21bslzP=dbqQ;;9p>G3-(Yg&ZhzumY4?)l2@AS|vFWW;N|Y ziv(mHkh1IZ=g;H!krPpiHlPKz8PBY7B6qc(O%vW4N5#4DlU(qXm(#(TG`Ula&YQ( zObjFJ9Yk8zioghwpZ*sPx+ZOd=|%M}eqh&Qf|8%)@>dN7g`}+93bXs}styh%8k(Ar zg@2cjKmnEDr#Isr$6xUjIE%-Cd)EeQPK6RLYHpT7vSv_SMJiVV;<{k zZR!S-bGu);+-JCOB>qe^nZDLDzRgYZyAIDRf;+X|T~LC1RaMg< z7o8UDE#}`bO*+%{^Rt?v?2T}`o6(|Z)$oJ2BtxV^1HagGYqWrPp?q|v&q5WbMo`;g zfhuf5LPFV4D3mDrAp#b*3TAf&H-5EP!ft3}$L&|mvq}&eC@M`n-+g8Mrv*0zbQ$I4>LwitKbpfC z#+Tka1Ue)Db!S_j&Hw_24PbO$!hY8UMj1(qLe>8=VM8BB?7Md~Pkw&94gA-0n1o_l z#JV2oUoO_NYP$HgS(aFRX(R35;>7uO_p1T%+WNXZBw9O~mVx1;0OfM1PTK)n8RDUa zcCLKm_BUmJj77SDTYDFhW7H_|8!%_coy~zSfo-$lA0Nlpq7Rn>4g?U8$7sNk5V1lE zEdLZ6(=BJYtp#Tene2hjZK&NZTvfk4?j_GWT>k#^C-3|DGi>7b@4o~paT3rlHn+CS z3=OZPV!961OEe4w^;+} zq#H!Z;F*H~V;T*=;Tnwhyi-gjvGd!=<25@w8EIFKgGaoSo)*M@u)f8H&6j{GL@wlV zYs&JMTCP?mIhh-orCa#!8l!x!@kJT=j@=H-@~c>FQV`%mPerK){nPLzbng zIU1LVlq+cZzq}$X_Be9)7L~z;I0I+}2vb2-mA-Up zYp%v`4P#I^%G=3;4jLw<`?t)3O92~$&&IcxfsOw0;|G%MK{x@2vDV;G-v~IeB9i~x zmuSq4fVLqWDx65I&4N1%AQXMAe@kntGGI2y5AptnS#kJyzu_&HC8#EaJRNN~t*;C_ zU6tf;SgEUa57{!*`$>1y_$t@05s=a^z9vps9W}gYM-=#~JkcdK#oAqk_?VaT~pF_E~E{9qC zrR&j(g|ydbs?Zc8gesID5K^T_{O<0q%c$3x4I<#WDsC^_DC`#;7bqJWzd#|_WX$0& zfS{3ZdEu+!jX=ng0!t8YsDQf3C5D;kCvYh8_VD1;TB48yRatzN6v0=4cTLR^DN^2~Bu7Tr4bbm74sN_V;Jfyq2AMZtRjbV! z&HOHer>ocGOBRwC!x~d%C+_L+IJB(>0>jPC3P2)}v9Zl(ztHKOrxqU1OVdTXdw;1m zqNDwThTiA6-A5-gNT{oTyYbH9NnEp`l9W_HZrK>Fl#-*Pqj>H`&1x6>hUnghJpBA0 zkO~O4S6N?wKNFlmfWRciNeD=e78Wv~HStQ7xb0x<_f?x%IbxO}`$jDuGC!-CfHlciI zs|0$tad!91t&MLX_ESH;5)#idpxw4MFU9m2>TU=UF$o9=q&Xx=0|hzppg(c8a^xTv zXlAryF*K9BW90K^ye_&P?oJn5kAI1Ax>0D{uB51l&u|%*nr%7%Jpbl^NFSJf)TuBTJLaL61RCt zlAU@-h)FM@gby2UvvuF4UED;d&3nK4YSPr9)175UUNXhidm#^bKSfc-xgVVT zcT0e?2E<+-iI|)GD7P=uy$wExo4Q9Tz-UlB;0M-gicOz|0t&y;dzkus)oL`!&iKX4 z@x0PhNH%=r(`T3?u+He{=o;I1Z^pH204dmgr=D`okJR#YyK&ssNVAh$-&oAYm0ibR*12I%Hbg=rZa`5jcI#g;SbyuVv#M;t#Z#*Nb zTKz(5VSEXb_spkhb1SPph;CE%xPTzss-ORq!}_z+1?n`JCZ62YJ9*dHUG4|RJ9D&g ziv`@7c7Ox=pS)n0My*l6yyda%h#s<3d-4P!;&VY2xu&Lu>4+S0kbpPsc2@L2n;U=l zTcq+rURcL+JJW^Htb(*CNRLQU zSsOdmk3cyq@Xfe32z!tFjQn4$hE&?0J$pt%7Qc5sW$(|Q&8-2eEO1MZQL^EGTcu}w z4-6cjfIH|59> z5&YP2n(f_`6DKEUv3?`2++ZSt*6MuELAow!cvuH~j%AC7q?J`3WTY6NtOx23r$D?D zjoGRFK zOs{>=DhmXa5T=cNL6_Zw5UvY`nzDX+#G)543J?%m10aIIf6B?hM{_iKyZpK(O%O3p z!GXwx2&qtqbpH(9~`I2$;m0`w*ZHnu%`5TeYXf|&`*Y|)B$!wX!QH4 zhVsJ7?|O|=OY++oM5aK;1JVm}u&8C6lAQbp44*F)xaJ(#U*uZV%VHGkh^Ga*Gn)^q zUq)$5sEasxQ4$&#g8xBcGN8C^Zfr0TzWHS<2su#4k!NZET9k~9)1V}G*8OERz(TNI z*qB=0umXhfVmndy^~{bpFIsO>t}{ol3is!OZNJ`nw+hW5*7X zMz&q7-tET9va+uLU2_4?4)X7EyUWBB6usbskq`}}lj-Ko&{4MTb8J;fkoyMl{0wAd zAj>5!EG%RQI6!ECfK@o(LvR+Cn&!DjnI=@tI9MF&{3k`Oe|ta|k@NbAYB5kFn0arK zg???``z##|To&i`smziRRmkV|g1b!HcZ?T)reRfkP;&b8X@JK~_m=41KwSb3Ihk9c zyjn*$T~gNcmI1mU2fe`JFyIr4iTf*v8cTivF)_qH1Eo(JwPBh<&b#61+t&$W{4>T8 zE*vm|Isz*2faL4E7#D@PE4eNj;8>XkQvgJ;25xv_}sTEM`q#d0*Fl-)PH8+ zh(SZcs=_ z7O-jO4u`91^JS>eqsM~!o05-J4Jy+8{X*E+;V1C2fOd8t{fSUYUOuG4GzGl; z@^JOSEj*A;*?SzC6HQO(Upg5R7o@2*sW=B-y936C=@#e6qg)7{;b=kp^Q)tF{7`t# z13CWyCiCFn0J=du3LGZXgyap%yWTjcEEMT$!e@7&h~Y z7wlA00FQvB!32KDbjS|Q7svtK8=Hb2$^;r!PWgyrc6X<&9wk-_gapqCFVr5zcGe`5 zd-;f>sHuIh@4aD;Yk#CXkUzfjbCu-ltHLtN{Z@SwYcmG!rgo{gTTgy<3qO&wf#g)& zIAn~j7~pZA&PO$*;h;6}#m=G7V){kj_V)Fnb+1_ceA77?yFE{t82+hku%o)I&7`K4 zJZ^Bd4!D32AMrmO6}`87&taqM5%_N(U68G&jreoF z3AXVYH*RP>_PhucwYVj&^z?MwI66?Q7_x(Q8!ZbOl-6Wb&-IR-B>BYppzTmx)!)B= zBgy6KQZ7+E|8N1AneAI|lrqxL=yxTKgZJ2*Wb-)YLGatpJ!mo<7#wWFIlbd~wQme~ zyPy)*YXF8G=|`YFEULC&%TtOlF-gIBEo|~f`uh4Cu^ny_2o1NusMU?5aeZU9doS8! zm*`-OsP;QB{GRj6=k>Lss7Gmu*mQ19&KnaM!+1Y_k*mGYv4g%X8g}dVxLDK7qes$E zd%6Q>*Gv+eB^nzWg`I=_{7xSLbEIb(bUdkA?++Z8;}R5X!@=441PlOR;m+!mvZYNu z7emS5<_%nB!OyG04R(s3N?Ell3@iG`C@DJvPWhs}T7?GFR})S_ zlV3V0wr0l}=;`-TAAH)5V%7eD6a$e%t@6E}e=a&y?~DcR{l4gt0kgNQO{{SpIFCVC zCj!K0MjwJ}rB`So>qYP<`Iii#BnTLYW>>mBBkEs?_g zp+zYvcSH_m<&TSmM66ouD#F>6*lt#!wPGk-YWCeK64PN(JnELdl;?zXqsZ}55RO*zLBGYk$FfWgbi8p++~IP_g7x|YD?Uv#&$C(T0HNpJ&ujM)rD3H+~v~n0^Vm z3Ofb|NRZBr$7a?}Xm5i|t|(*>gLjTFj*dtfUsW*C@MFp5&Ui2ze3KR-WS5F~vkKKhrN zyR8j&ly&b#{Q{An*{U}*OJop@f%14V{0|3G9>KQL-)51c817qzi8yVyWVs_S8GR^y z>>&wJck8DXebJ7~ome2|CdyEYj|K(>^*|Bg1904sgN2~s;fG{kfA-Qn_88zOY^{=q z$58}%78Kw?WB6tMT((CLpULHAy4_1g%@xHn4c|glqEK3(u>&V_)e!s)<0RV!Zptd+yC&@kU`1 zn1tNZ89D4~u~Xd71D*q%HPh`O?d>h);Rd)0j#>i}mm4Uxite7>7|4gST`QD@ zxs3)sXlSYB-nv905sr)ytkU&1fcqmmUwAe=4m*zEV1Ms~ZXawLu#u2$J9Xy5j?qN$ zc_WOMKVFC7{Nl=R?y}on zNQiRXcqgAo%f{BhFyDw4gtN4{Py|2{{K#1xx3#;=fIyB<6&(!J9>f8Y8ajz(#odWk zmqalkyJ$!MjUv)KBaq5_bDu+-5c3)hjhJ~~t_u7o1aNe0K3tX-a<-e{iTmQUhnsl} z_TnM4?>s%MMMU5zRqd(`WaX)S(e6j@9Dx&M3Y-$;P(J-LpZ@vHIXK|p0)h1=AfLxz z1qeiR%*~k@F09Z>fHA|~e_V8MqHGo_Ba7d~b)R>Le1ur%EGeZlR9KKBe+XR#K){=g zua4zf2ooFvophiZts5-g19&GuS6YrCcGdj2wWe|6&Y8?bY2;Z%`Bq@V*dA&^o?qiU@aaYNjG_;ryK4#MqQqz0I#d^X-+&`T6K z(|z}5EF|jS(3L#M%w8BU6=C%t;hTN5n|RbIvR^L(=c{LFk3clA4liH5YWj<`n-dXf znO5iB2(oEX6pjB!ceJq~6f7W{jBq`W6ES1s;|vFUaH?RF@@SQEZ`{9Q&w_vce3&@+lYLJ42%U8 zz}cW`NZMyL#3LKY!9bkp)FILhX_y!FpU-0MH?;`_DWO)~>jE&0+1-sx2Mtc)21-%m zg|Bb6&(QT=tP^>cl4Adr-0|^`4=PBZ+a72-&VmV22Wt)x=|LG2iT%HWdhaplN+1$M zIe!Kp4(9kUISH}8DzTvVf5f<5eda(3h3O#$XIZ9&xA~qO{TWe{l4?#BscD_;`hS>v z6Q~;7zis$xpdHDk&_Dz33b%?%Nwbt84a$^8kp>zlk|vePSd?25ASDqPF{>ed&hw(n`PNi^gI@46m~Dmk`5)>Dy|)4LD>bKe`u zKrb%~l2u@Jl4kqEhgB^>33tP=PwggT7%I5ja+TDLjcr_aQ=@S?ZdYuqNNJqP(L0N_ z6KA^9uX&koPr2dglP4FoMrs3QnPKB&zb-kM`yzdf*!-2D0|>s0on(*^@}eqCdY8~3F?Y1fA?$Wk|M z-69>&?Q7TM^tg+!oA_TdZ0k`V2eZOk29Pr*qih$&=A2b-x)$vcLNjBB}RUU}?lsC`)X_RiDA zpVmn8ek#P=h&(PxVn~zu`g*9@xFS?SSq8`0`40?4{!*S4SmQQ({`}Qok;?3h?dSR6 z@|N`Xz3o-)uaKRks6{ z=Gyq1y}w*bU%ze+m2S!LqeS)=Rs*uhW zx(VeE>hj(MhEFnUvcM1)7r%)~mNU8{Qhx9Zocu5rb7#wC6pmNMCfxe8&!vk$!6_{i>m&EUaQ_9 z$|qu`>x4&5ZL{r9MjIDF&vugPu8Zu!6n2jG>!(pOXPhYZY)G%O-GRYCety21Jxdf& z^&raNYb2@_S9P;kvu5HYM(eql9`Ay8?ED@?t}j_Ny6or@@2gwBpPZQFlVUVu#Wlpw zM>#)^ySKR74#mM9hQ)i4oufd(T;H^Dx^Q%-r2${EnD|Sn%4yT5x3wlGytDn?YrEjD zzYggzl6EiUAk|^SH6L2rG_!O=?WB)IMA(f;Nxgt!!R5<(Br>($SG#>sAywz1{n(4U zGoP!x=^L+WWO-2{w`Ts<#b3UD-JP(cJ~A{soE!uwyO7v^g}y#}f+9auf``~Fk2$5{ z{Pw5R2Dg0i6gco6k?rs01jP-gKk&2SO*aS-&8XF4&YIdbjYw`u()wY9g&R{}pAeCnb zy`o%b(7aC_8e+~L^aT@w5>s_;(khf~cXC-RJNoQ0Dj!ZpNA8#=DQO~?$H$sD(cH^R z`4FCVo`8X+O>|Y`+=xi$_}&nmmHsaPQ9h)=(w>qwfAQi|ra}E|fi%xch;b274WhZX z?!JPxOl--$07VTA{7T;3!zWI>qnZyJ)AiTSrhAsZd>P&?(!8k4=k1j5_AKs+Lb15^ zhb68#Jy%Te1&9T`8L$0~wFjO|wph1LPb%+mu>EpT&Qe(EX{9FJtRt>#mAKEX+Wy33 z0c6LVXz*r8qh2@Kmj*H88Y$L(Bhhh(*ox8y{MrW68mjqZH`)GQRC-dX%8_%=Ns|4m<>|z(D&umV~KNk5Z8^`k*zfp6~X!IjD!Y zWmMi|={jx}Qhi&ZY#md*mNAz_tWFrLOeQgqxLdley}f;C@Wnzg1T3!T-PWz;KArZ# z_|4dD(0yli<_z_GyZ;*Wv=|+BC1*)0E?RQtmt4YB3B)3mXKN-+oaitj#nu71*oy{t zGc@7C+V9XSAOPkmecGe*y+JE@fO&Or$$ptIqaT*d5Q`NRtuz*62mM}>04EFo-kY}T z9UWy32I+~|aX#TvaeFz+)ZGIY-;{WnG11#Vm?9=l&#%{kHl!8{zL+=meZ`%tXQx)L zVt0o0hA=YG&$gETUn6o}W$a=Ub#}Wi{E$9=KH!|xr;w_SsK((%d$Q~|r=VRjq7o5R z*nL`K@FkgtRb*#*iCq{*gA%`qLg#&7Sq^F_SdE+&-@@MMMwesJ6vrms&YrYL75R^aa$_xl;goo z-FMvkThxxv6LhnR8}Af*UVl5&eZz*Es0a#I@dOvakD@2L)88ag<7dP=b8~)PuEU(9 zE%n)ZnexXzb=@r2&pT7T^u~UE=(uAC-?PgBOyJ9{cR{6T&1k+*ft^|4c7mn$WU<~# z3MW2Qcn}paQVBEi_uyu+MX*ju-9<|c)>0ev^?5HzNh#75u(w(D-52ZBT*=yhSYW$e@!_WB^vY0!xb$&{4y2phUZDBaC-I);2h;JaMR>AmWj>v{SoF))d6bR|zCs0rzz`9)bWc(ahS_Z|WD_h9jSl8@j=lM@ ztPA_zO%2;U&oNVu5qeQvTtQqc|E2}D@aQq3T45?K)s>)31MR$=0>;%T`PC z+NrNOBhTs0hB|X?0qOB_Cpb*vy!5A$Rr#jEYU%yoUL7?5d2Djr=ZBVmPe&jas8CSY za1$fwtEj(g_g3#Za^%Qt;Q;~8-qYQg-ugC5!|i^G{En0NWe#EShaDE++(qQLsOwcfE;uCTHFn7PEa6VJe zA;b86R#4w?6Z88ds*;ovejP(y&Oc64RC_f_)KC^Ggm1C|vZ;IKUW=?~6giog`$9Pt zRT3k!X4|$a?$_mG{m&?H9Ar0oFH`wso$}+m z%jR1RN8&d3883~$zwVt}cdE9iYPlE9;uo*y3wnJeDX9%W&t z&D3L>wh=DBewIWU+ST%>ALfW@bSWHpxoP-&QNyGON7t%6lTJ63f2raX1~Gl-C5(@t z$u4Us2=D#qnu_UAkSXUIFrV6Iy-hrvqrSH1?JBQP-O}E(m22pp?5kOe z)|bG{X4LWSrfni&K-IzByV_BmM#gw{dLo>a*LA6>%yTq$W^<%-OMUKw#r_S;niO|D z%>TTDcZ0O@hruW4?{6zG=G{$l8dm6}-~MbWen?O~v_Qtm(ROm7RO)j1)o)3eIYYcD z{r$B|1-~O_S4@{1tlcegA!>zm*7#$B++c0~sabq`iCDXWZ?eRfHQo{YNibkM#O_iu z47?9)HFNiu<|8Z526}%{)bM;%XM1!{*Mk~|ubU??m*!=!BzvQ-g2}eECm-Csd(u>o zm$S`c{&Ydfx?^{k;wP)n#u%p;4)ITf>4BdT)e-zSeg&xAq zn@3H9XL1lNyPw4kO@d1m_O-08{e83R>C%mcf^*jS?GxIoG%X+L8uJy8OAKoh5hpMX zw1CtBh#6+038ulO78WrmLFFjXcFn3P6a63_Fy}ylyRg=-cfS{gUmq9UKNpX9ux)KL zKX!FV9%{o|w~W^O^EbJb^gPo#| zLiImN4E>q{e=)5e%O)iZoX`K9WIJo=vG|;pxZ(!nc=K5YAeNcIFctsSOY3iLa7Nuq zvSAPmpTusubDX`7(1;RCK|^_`^dJ3VZo}F6Tg|6wHlN=ua@uV6=3D6ZOCJPy0Hg&W z<;xWw#T2+!X%5tfWMUK!4uZj~WqXgA!X4}oJ8$mkg7P(D&VwNaaidbMUiY?sz2%!c z^VO#Ln}6?acwDt~zTxjx6*JL@bMXRu6CgeT_>N^^lf>adqbnyJT&W}Yw@^QT?reOvlEgrD>7xJ`_ojFy(oe`$)5o!P4y zJkU$Q*eke|iiiHKwRXIUFQ?lB_c%E&srPP1ld~iZSX@RK=-bGMk2ff4$&ObuHGe!6 zqU8@}%ql5!H1VMmIIqIsPmc-OhmOFxA^#Am$q=bQlw2ui4uccy>O2zyF1eV|h(DDT zWE(^oBbq2icC6R}s=drOC9jkn*dC0eH3)P$U56A} zI!C{EV#d2tO6%`>x>3VHNE99&VDDW`MXf|$hqu3d+sS=)+mj`FMVtbW_ZFTz+z?;` z>L)-kv_Gd`lVcnP33Jpcly`coHaR+e_1(%Su7_F81J^2f8lJ1GTY^4!>o`}CE9@^p z@VyF&?R-2J-0_nYt#e~dE?&GSbuH^0TJJNqrT7r5^7AeX&S=I1d2;aZiGD=SVrW!gh>`W z#)@6Ghb?3L=pKWYQ084_oeci*dCdd=Sj(iEf!qu>#4P1PB`7MWTnqZu)89}0UJPHN z!5{(h2zZWvJfjs1Y~XZEj8p5Is{qr=Kt^IU%^`GC+2Q%Ii}OP zQzBU+2$ph-7MT&bn1_*^jfajUu@O`RkW73geU{S$eeK@thPMK$h6>iTu zZ|{d-D8ph)8SntL#Da`p5Yn;>5WTo1yW#-;;+wLXUf00qQupEA5777`1im# z35yDM=E>{EA1wfzX;UEY!YL}|!UaOX^10A|N=V$s-l6$|kdP3li2T21t%B^Wx78$2 z{n`m<(8Gu(8q9}p(jqcz7CB#$5d-YDa3OLF7ap(P$mAV}ICA6-P$x12fiMZv)yR|v?ZW5;!;jxR)KpBQxF|Brppld)En5SD~A1T9UX76 z;)-S-fFlDy>fknVLqfgq?9e2H)8SNFb?V-$$u$EJRYpc82E=EqDcp~JFg_#SKhj@r z+;|567Cah@F(bigR1-4n`7j9vSL7jf7cmVQf6zVHvWW@$^x>p3tQS#1uS30u=Q8I^ z@w5kpkKuiTrUwNbdLa+2&hOthfcydmp8`y!FfIZ^_qYcW zdJB(dp>?JOGDoJ*kIOWg9CUzJ!du&sx3=SIGdOKO6FV1^G0JNw0f;UD%>qL80vVYw zyu}q{Pqs84D-}e2~0@S`@Kj9Tr!Oo9el8 zhP4?ni&7BM16eEMkyXqpfD{8<`Ue-6sbYn4YPGyGAj^0`wo9QLBq(fgqQY<5B+|gJ zL@`qX1p_nB(_0-JyuX%+LNjQd)t8>GMh=O(8OAkkX|4bPtuEq`1f@dydtN(mw9Qc& z157H2&~$z{HeRRbj%CWr($cptPcHy5yt1}-R@bsq|A4;>v5M|~El$mpCroz}A__=F zVBnmBU9cpPi@gp>g{baO!GN!EBP~tU&bEDrR=4Qd1T9Uu*98d0W4~?z`c@elpNBBT z09}{%9SA!|jvxPPCZnr>{`2Szg?Fd^S_60Ii}>UC%J$-tl1i{2W<5|^dfO`FGBN(8 zX<;0+^YIzLH6Y*t+@!k!o;L1=3)(@L{H>4S?5GT2T79w|9Y3~!2Od;8ziyrrdo1gPU9;pnpGB<6*T;}S5$pjtpIAxbffVeucjnrr%ohHxp` z1m**b!zwXS_y4IumcVdnk(_$gCdcnA!3qp-H1Z6r0c>iI!439~=%k>FQza!+0V5JF zJN&CV)9=^ME1G>+X@n7mRqhzi3E?a~*ci~F^!LxEoQi~n_ygpPj*^#s7q@JqH6ok0!2AHhGv4(pI46Tru4AmGT zutS{?gK5uU=~GTRQ`~zgPytm4)q!rgBYjcvnw}uMV8rLa)sX$$noR8+rZS* z^_w=yA;iGd`o8%*#=IQ^T2z4`qARRAf(bY!C`-$i5B9Gj)5xm8k&W`gs0^7vn)zT; z{R1W-)C#vYEV#s=D3hKY&tjw=EQJyPo+zNHZ9v5UA|t%8z-V8t#;|$OTSx;QWClDC zX|XCOhGD9MvI750GD$GTK_B!9mp*@fcJyPW_e~J9ZY1%6 zHNZ=RJL03g-DtaBSN9;QZ~PW6dBwl)l82Cwbq5^{F2};t^DbTjG7e%C!!0~kbjzGC zXea|dK+7C6dJ?08{`I{kBa{cC3(j}h3Y93NA>|h|4*=#)LLCfOCp0PfT<{M?JPtA~ zud7R?`AGGnT{Kz1wcxU2Vq;hS`$aBew_$;7R8745VJASH!vux!F~gyp%)*$DZodK% z3?h*4k7qM}Z&Ql9b4QVz``@=Gav6G0umzA_NF0T*kdcvrT9TJ6?m1u5Zre6}^2tJG zIgMjD@FgJ?qWPBxd7EP^Nm*EBdaVL8fU0tG8^J|j9|6vpBFH&3K<8RZYpWR;aO5>H zJUo2!T=~bVjZL|k*uFJJNI2jb_qwMHC?Z=**^b?dEC_&+@ zgixHFDOw7w2?3GO3W6G(m%ix}2Mj)m9|ZX(>WJOmN^vk-$GxO=!J5Xy!}G6qJr?#F zTqzv*@Z9UIInxM+Jr&btB4i@*&Qnk@!NWpXi@1PKMip!o%gF<|OC;+&`n(o+~l?-@qwM9)VETYyasGApVAfo7vgc3c17gfFpXrJNr6JG6B%z5z}^+ zF$AVXmMQ2m+Q(#i;KH`TlLtnV{>ORT-Tuh<%rUZV{~j>T`4t$D&FQ+qn?`oPcr=fTt%fAjn?F&3&HG6xVH2Y` z4)vba1A*1>?ktDORR!cy+%0QFax+{S#Ll=whEZJk9ee3MQTdEE3~>z4S{d%L;M;L? zD_;F`dty;u`QOS_#eM+NxCSE7a5N1TsLkNtk8+aj5+s6N4h;#u1@wNi5iU`ipz6iO zm>|t9=*r@{9U3u_oe! z=6yw#_Wu1f2sT$38oHuN!=eZ1bxW1EUT9d6qDQEy^soapC^>!^u;aRo`V!0E2%8CV zx>FUcU$zlqzsh>O5eB$t7GyEfBhcbv} z_*hhM*CD_{M-?AGZwXcvK`3BXAdH@}7eSZ-!i4n{^co|749dnrkNK!NCK4)pz8ax1 zYQw6mq~Xl;=}91+19C8~6uys6(9P`~$~QWnWL4)a&8E>XM(YHfQUMnL-h=(4#yU6{ zLL0k>t3QrvPq@rN$BSM9%?d>_h`%5({(5DtG-L^oK$G3+vl+IP$TZtU!swh3c$n*O z4tj_^^lU4Ler7tk&k?>+pxgj>J6WSE2t;7-hcn@VyL)PK6w(cvN^j^m059V32`g+_ z6ab+-^*pGj_40-S`;@i|GsAP>)&=+TMe7eDeXWP}Gm(E6TBVzU^@is74Z2lXuOr3w zP<~)(Qhvbwzk2109H*NYK7?z$iIXCvP|F2fe}D-g%s%U4QfskNFcBu35O7ve7YJj; zVo4;OHolAhAXLE?cQsZ9c(qguW60CMM9n2b)QpU?WA8=>cJP&+IEmJtfC-q5UZhL{ zk5q(q$p0GjO)lXXkX9@Bb>t#A*8(mo*YzpCmKeQvobn4vvuoE5vIY%(ghh09B64w8oBIlAcpgO5loC; z_2F^;@= z`TF%4*c3}i72(ttHaB8~;(GGZ#vnD=XXDPDx3G;!L=M+siY)YYJ9mCrQ!Fe3ObNXz zHfT&t%v`WUknDg0s_C#tmO;hMD6W{k&{Ch(IS0HJ6yiv?(Kx)o+&mf(jMwmh=XYFpc5L zer!rw2LgG5BK_L8)V)D1!^$^A@}}M$`2o%E1)ZcKoOiSR{s*dZPn`l~C1^kN(cVoj zrv-C>%6aG(eh)o8ru*}k6- z(+XwrU_o|)-;;!+c0#3+bU-?Nd$IrlzNoz^@l_qgD=VwN;TH_F1v`4m1Vvhu#QsOJ zoPpGoX9x|1H!}JIa7$9GA8&vb0Yi@J>gsvn0iXY~tVH3=4+EXMOvN5A^ zG2ej5dyDb(43v_Nj@N=asClyS6#bybUahBK7L?oqQj!d? z$5xEs&x5l*8%6}My{B}^azXnCW;ZX{-49H}1t07Ux%2`mB#7?Sfn9)=gL81O8I@6( z?BNwPQ`7Viz9m_0-fzsdT{}C=}blP}~3%|81!gnrar`SUXhZhSfx;vP3Y2 zEmEU3AZb5zu8<+s9qJl9Vv>P!da$Ius0{QtJ9RtCiW;6$UQqx08v*B|c!%R$Hkuvu z_Xxz6=^oPUlkC;eMBt{3efRt9*L!L0^3WQX1 z?rE{OvrjrI1|2rncR&~9n9j0_M$#pC1W6Za8`ND`O<0AYAwj66^f}Kiw*)rbs4E~h zrh{?__VDd^SoL6g@${yzUtcN;01%i*Ss$q$sa0c0PLrAGw+&!3FvYQ@67trCB(MDWSYRxrRshNS z_NCeQ_pVh}9boz9`UatleWzpI)IBH5Y4c z3e^(zCN+U&GqL3Dl%O^Kx9lz{$;$ks2*}Svud=8p0tM#SMH7n&8G33cKgi%uzF|o6 z@s5264IeNQL5RYkSeT#1dFT}ZEcuUxKf{2p)E;I?$i%WNUQHCz*jMD&3+W0e@C6F$ z->FIGwR(ZIkEa6vglrt5a;XUM0Oomg?M^A=a$?u8D6Ryi7HHi`gtLx=FPWlJ zr-50~T%09{;j{i&S#vjlZZgYH4M_x*1Nt4R3s808`9YcTS3J{?c^S{qyAl#JWrP ztv{J|+V1%f!`*!J=%2A~w`S$aGW1$3&Qdm_#0blsR&?9gY-XICTZUSRHe1nToEK^1 z_hSX87)sKEAAzl}QE+cakUM1~AfmVxn3J65>@%_kn<+_43U$9B-MKsqNc3cQ|6^z8 znP9YX<-cHUbZHPIU=ovmRv%D96~|T$t0;B?z!L~~xpZUm5CN&2;*RA82#1~YhQbLo zXxOZOGI6|#os-kb+>s9VKWzXgoJUTakYNdd*{j%#Rs=KMw`h|8AoGZd+S&=%`>UYT zZOi>VlnVimkqGA-+h<WzU{Ib;5??wdba}FwLF0SyRy8?mR%*PLaP* zbPa;%c^jRPJmJ7nY_#)GcOH{63TnNq)1^)atbou#>SSPlKv63C+m;Rq8Gx zN*R!w9~m%&egU>w1WRGEPG)r|HgS#lJ=&izw_gsn_%`#u=~JS{kn$<`T^$Bl0Owh) zhyMZ+IT&cvHAP1|#5uq;nuJ;pp+PjJYJ?4o@7?I05qPMoC!&Z{5F5+j7TI=TaEaOZ z;M?9X;5=MIaVGGZhDJjda$M5iV(bKjE0#@Lff=pBt)X;I2tcOTMVP_yeC|CS z8R-gMJWc=1^)cuV(s@3p+ijOA7u5d-RDlyG1j*wM+h83K6#z=Y5?U&@f#PCfJwtWB zZOD0RCg&Py(70g1Q7Iz=#c^Pl6qBWZjSJ`yXpkHlXBf*M7>(h|T7loeWT0lvXfkH% zOi6ILZnqkYL^0{-=gu=+41W|1(467HN1NAP1Qn9m-o1TS{#lOrOGN+z7G{>bld;TA zSq&47W{m6dv<3i8!>dm|jgwGZI70!Ahiicm0_~61y9gDimnuIPL@@CXh`GJu^|N z!wU%R`K+l33W|@hH86)~hw@`4b6(3oPKq(g#3-W;cn}qg*=xb|bV3s2%EqzeR=rXVvn4bRo zo`v5pe}(Gg-}`NbP&4*Uvq2$&X(aA9o+jpSe~sOgt{02co#Y9o^3DG9=5nEz!mybr zZrH8U*VlK#^5V6h{h#lot!;~j1@Cl5-WvK%ZG0MmVHY2 z?8=T{I000R9lFXV+vd;R&HG}v&uq_99D{^0EI&8rg?_s!t^t(88m(Bt#dKwR%*Hr^ z%*Ftv_=EFBhngasfvts;9vNo9<`4OZJs<0yZ1S<=7T{{p-p`F;aE5I!rYtWy_TorY z&SJ4b6^KF%C-+4Io_fDiCXf6tkWA)`-IDrc*z6F<2Vp>R8s|&?v*L46?XeEQKtcEeY&4WXEyz_MR?Y%wTjVK9zHx>x(zSG6pO3g0Ywtw zPc-9+h+vT+CEV{zWQqL6ac1D$YnC50=dvajDsd(Uu(K;@cGxdvyGZ>BefHRz4cdPU z1O@n!kV_vbO%Q7Mo5WBmx`IdfXGxYgdvyJFf5h%t^Dh^m^Hs>r`9j0L19#s)r8zf< z-(z$BbSbXQ+xR26x3cc(?{Iohc-%8ZEO}SQlN+PW%hoIP-kh3PQE~s8(=wIBl*AKj zH(fE~J^2^!O1&j|dQ(}vQw7-fIy3tF!*%8@j63iu`-SzV)En}TtK;{)-hbh~M#7#8 z-5STKf<_ut@$GTKzBQ8@A>|HmwF%rz5ZBX-iKthC|i69r%VLxX7uQ$GC&U?*RP4NE(m`B-H>Q z{T=Jif>wwd!01TvGG6=k(cA#nXO8(Ho%Neq*Nku70!6Qd7Ux?B%|*{ggGpQnAR(GF zZv4Ij;E&cwk2x^V`Lh^?TbijKLYI<+w?_Gk^B3kTD_7p^!|{klC}EQ?bK#-{=JPNT z^#Fm8+TS2M5f+L&n#v!_Fm_#Cn1g790*}LF3g-#UU4^RcXMcZxi$As27|~v{!fEQE zOwedcN5^_{3X#yffyauOgU^?UE4Z_G-GXVzCU|J|#x%FGiZ|R9NKa?N zglj7~@53abPNW$*tpWJDTj=YD8t&|`vJFf@4l_N7J2-p%X)Z>=6RjzrewWeVUo>z6 zh*aZypt!jBI!3JcKFp50)g81RiL?b+3xpj13Hw;L4i_ zB>OtV5}-_&d3fA0h?MBq!1Ed|9xM9_ZHa+iWdO)3UDRC@4STe<;-ysg5Si!+?(LSC9E;F znjXWv0F@895UKbLcszUlTzy0pOO$-TCWwz+-z=I*5%?51nq_cY>?-0~atfT{wqX4W zV{N+y>*DKc(-asr9`Tt-UV>Kktc@(sOI(bK86!5$THDW$+qI~3STws?z$Ym%B$-`6G ztHt!V$fC=2#S&^BI#}?+v&Sw@))nJufU{WPG=;*YCRjTndSXg_wTlxcm@HiY&Hxs@ z@jL<49105?ZK*@|PgDzGJUF*7GXpLriFS8W6J%AUn3fbq5xZiJE(BX`=i7_hDblOtU; z7dWDlv@nymoq7YDR!M0!>~CR&qSGuC5QsDkeh|Fq2RjQt6gTkm|K2~*F2WC1Hh$<{ z;|C#?{`3F!KmG5$@c*Sd$t}Ht?hunRF9@rT@i^a{5J;z&3MznieUse$Yy;1oJ?rdL zePZU)%dlBFwwjxBJ3S87*V|1JUHr76Nl#C2a3sy(ox&G}NGKV?q??(dC(=F>?j(jW1$mrYqGm+e>sDz3G4Rd=>KL67dRo z;-g{NFU_)o8^s|$&RVE{f#4*^%eWntr`P;HUw#sY_j6XS0=nenMGnu0TXNxuvG~C& zgcAsvs{g9qf)m=oL7IPJ?2F%m^C>)dpImRx0)hGg1_Nhyb|R~>LV1pjeRh4K&+?W= zP>CqSVZH&LEw=h!^6&hflTe23($ZeY1U?L71M8Ko&9Oxj@o5mw8wDn{hjTcfGg#aq?a0E94bvZTB zco|*|!eaB?<29?IW$3(K&?zMLyMZ@Kqj{7{WKfQqRv7k!Ur5FY>>ScVBGYQ@)<*wK z^jV;>2>$!OW#BemLahzu`U)&|R9oHGI?}+3aB-oE2}^~*v)i|CbJd2?H;-2ij^xP(3Z!5D>=_RNe;!=E(yV25-H&Ok$3?GBsdc5?n<%qAL1F)q=wo6d|9{N ze+pVk?Ow*ri(9bDEA@By1#pdKwcYAU67wo2q(UYQ%US1iK_aXUI}pa{qM`8haxDH zn6AjISt&mlJazhYVtgW}&6mo%e=ZftUscivRULs9NT`%u@C2@TuvraOP;iq676|wC z4~Nute_2VzFsWijM}~Tv&e#HFDqScZ4tOXNb}Aa9j(z6#BhL%Mp;~c8c0+Zrr+C*| zFo;lGYHG#&wwUwY)t@3)Dy7!ImxxWJl5yLIFsUE4VNOgd* zz!~BSfgzt-TL@x0kvs6YgP)Ho^k8V%b&;D_FLnn`d!&=FFKB$&C-^mpSqKAh%&zD~ z4+4J&qzxp^$ET7;8lS3h`{wBn4qb<4*qCDF!E*sjgU0FADto_eA`L-)D8H8Z41@;Y zIaMfkNjHR2q-O8+RJ9@5IB*>6YXQ~+02OJ$KMK> zXj~#{FRBPIkdnC?WM~ZoEky${SfUkv=uqnuKFP}L{!cei$a z*ka>GRj2ByVq!PQUM5Wot|MsZYGTaT_2(Ld02ho5nEb|wP-P;VM! z6pJ71!h{7bHHWJ!SLo;j{W+JOwytbsA#DM;bJ30j*x;PGqcC=n1L3P!9x;T~g&6QQr1Mb^iY(H@3FE&n;ud>swbEWPs2F3wlo%tMWcvHl+GxNxrS=#ECqaj300RC9c3-^b?Y$sP`7hW23pnw zf1>^{gMscoson5+B03NdPVuO^2b=!(?RvsT1{?`~3kJ+(jAAdEB^tD%*W>ByD670~ z-b*KfU>=af?Uvz)xMGO#YAk;JjB2R10xlQdb@pU4_bF4SUWTTt6>R^o15?qXX&(qo zVrkfdqyyOcsnC_`uI}y%>}PU)+pQDePHSzTA-vYbMt&a=+mSjZ744Ho6Nczm|vdDih&7C@VGhb1< zXCu92Xy?AsgguFT?_nP(C%|U?I1?Na(p$6V^^edrNf>vv{FDzt(AkKY(xDM046n%b zA=As{AeKxE-Z!~@qxRp}+GzB=THQezm4gpT{-`LZOoOoE+HxjG7o4riIguLqTRsLT z=O_5K&08+?GVynq;4E_9`$s~>%1~D-bPA9FVz#u{Gz38olzFTAX(+!?4^+M8MI&S} z12d7Af4Q$)IQ=M16sOEFFfAMDA*(&4F8R&73)RmNvRpA^h`5&{FaIN25B<¾q8|{@x1yCdLS19 z2A#z=3&yE=UZxC%Q>lxtx0eq!`GO^9FY z6Y^}U=l*^}_eaQBnBLO3&3JPi&gk$F-;Pmc=mp&NY#f1Re0B(MLQI;OjK*+R0gX&5 zBy2SCN9CMJwEM}i0GNfTi1BW0VYs}W4OWC|%s5iBFZPpPcWJfPJ69={D}vtZ%v7bx{G;D=Y#G32E9!64#c zVo@a}mwNUse~Re=OrzT|ct-mRI_J49UdaM1mZ^_VItpH8q)C*E&z-xMLBK^i$iYU* z-z%3t<*$l`8Z|lPH53wuiQuAA04T%`SW|=sJIzpIEf$US7T3+3m`U!deie95Kf^2dG9etTSKG9*(81$1h#OQ1O}(J zOJecH1ab2uqjHcwDgP%|b^v%Z@|XMxE}>deO6puxb1tZX20`$t&5hEY*9ilQYp5;Ah!35@(1>QO9Z)DU>^f}9^NW2`z}2976LqxU-?8~mdnAysRE%3^ zdjJ9>-*J@cp68OkX%_-kK(xoWegig*jLC(a>Ji6~&@r;WPRLfNA5*wB8&hq1V`cq8IwA2U%@JqK+BH~xMcjL{jg6brFAQpukDWRT6dwo2ts#69 zESti3aX?}Op3w{(y}?;6RoY*uenfrOfbE$YE*bE?=iFJ$1pQ$SM`yDbD);5&*5VD` z0BNEKRWT_SU&%V%QoewHDDJdm8yjd1O5N@oiGG`{ICAYCMuhpVxz(J8!{) zVy{>r^D4@!IJPGWtSh^=w4uSlo`!JAw#dNYM8iXoTf|r4I>_;|_25bb5pNu(BWAf5 zG^wQKbUdXB`gj7?Bo4SKD=W9qXddi>wF%+|kLz%DaIGmjLnUUoICuCcAlNT=tt&8T ze2BBOvT+t@m;@7Gi@7A)GN%|3kHn*oKVDP7ex_9WIL!!RLpy_OzA79%bs zDyy>}`(Vdwi}{_+dP&UwY31+@KX>e_d5;eb+Iv=vrF!A=xz?!{Vq(5{R8`Qgh`n!y z++z^sLiYE;Y)s)Xyb-tgR99EmkfDN_0rD|7m&fsZ+M&l2c*l#abrgpQ>P)KK zv+il3k8(rHY*_qm>)lv&RZ^az=F4Bu{u#SJ?fkKHZEhZ(S>KO9Q7=%CTZL*A7H6*= za`<*v!cy(l&5fyIHlNDxp-w`39@|g{`T`L)v+l{G{C9ErZob1Wx!qN7`EnKX2L;8F zOLsqQa97n_0YMEY&AWVlfp!A?Q*bexm0gP^338Hy&oA&`_V?a-Dr+3C*jrgv9`?^! z27GAu%%Rw2kUr45Z+H(}0dz_dFN)1`SEoea@PU9>q#TxI*qJpWms_?EZsGHv3)8o^zyh9uf=mK+V z!~JXU%p-aA5>bBxP5An@$pO@0l?OBZ?>T;5RfCw+a#u3HegxVms{G~4nGIYVD zg&=ANysp^(HEDyD)wj3Scid{L4yNA~&F25Ob4kKdRf?>ZmM%^oy1Kdo!Znnd!_p?T zHQw;|{^FzRTL+ZqXC_ywTQY_ppg-~i*vhc`Y@t!8>i?3CvBZ;s!@qf;Fw{_^A_)!)vF9VE37?a{6JpJM#!jMYphhMF!s2TETkjVb9bUMh(ac( zqtAjKl~`qzCU9S<%vUUNsJ-ZiTTe|o%0rX4hwzV`i`r8?`cXV}XrRL_~P_WDE=pa8+x~u@B#C^c%Tid51`1p(ol6B+UJCYowm)EcVS86kV(jg0i5> z9nG_6WzT=#yQkj^W3~wb0yCp@ob-{d;n+a|c>csLGjxHNW_2GqV1PvhVyA%hL=2U0 zATXbCPdIs?Ct}JR4EdV(T6@)|%&K_zE(r(VaA}@EI3Q~h`MEYh@`*MQtiPOrMQH7D zFj=)~(Suv1j*auqM4w&yedf|nrSakhku#W2Ph1}QmWu1$pLAefZ4R#cxP<0M*%O7p zv#F9UyJsMIB6G--hg&+{D<6@mLiQ#6O3FQEJOleEVgI0-DMtE}6qd2w@mZ*|EQIsC zU$XZNmE;*Mvj-F+U#F$i)U==@7VH2K3H?H+k#pD2pvv}`BF)|^1=Ls6W-q>?&2O2f zD4zmHssc6Tn%>>E#rR>$=~eo=7DscHfeNlgA<^~ogx`I~q~aYAOg}#{Yt11pEjeXn z3qsDSYE%K%3Md>v51Br^EAs45qOKbp6KQx`=zyvmqdchH+|_T|e9!7OHt+WZ^mq|) zX`I-&?vsWRKiW=aqNG&;l2A}QW7;&&sHNp-0R*(0cDlIizGiQ3ZN00FznOfc(MHUl z)U^mblCs9-#8Sr!5RGeH0tqbg5xamGN~o6n`OFta`_bdI!DF|p?fO-T{a>am58FJ zkjWy9n5%BSoGT}{l6v3k$zhoGdi-i}$=Qlt0#+;?L6Xgmua5&!`k{%#74T%}l!G^w zq0Nq|OK)%OYjA`lY)$S&rS2}{Q-C1!0Sw+%k#{v@bgh*r2~pfU2C%Qh%a;TBfX(1fma`(Vxc zbk9T*4y@p|ff~$&Kx8`QrlR&~tqMD?_BI|4nbH%($m)$|#ZD;#wBVYb<=Eo|-R>FN zfX!$=Lo7SNX;D_*{;Z#DkmyJXXP?Y@Y*x7m(hO-$T93BEQmUtDPNc}_-uzi}F_}V1 zkQ9FT(TANN4XN>+;m1IMjHi21QN>LNITds6+)Z?@;b+>xXE!!J(Hd4(hl6;XaIeJ{ zZ(~iH=yMX?0cj`zV43O!Wz35OGw>!Hhu$sh??(R@CUK+oqwz|BzPJ%r(B&n&)u99w zm>jTsIpW5Jz|sA%LOQT>07p0zrcc*hAXHvg_VJ^Oy3@YBd*>sl_5_eN0GQ)q6P*$w-nyFdhJj^69W`u+!GVm%V>~}h1 zFMf$nWx{BWY}%(z@OX(&og`U?Q-X|%Urbsfpoi$zKlW^yi=jJ)jYbMtUBRuH)^LFU zm`vDrQ*-mHzk#F#`QFyhF`nfw8!GRW2?A9fX)o4j>uZfL~WJFWBX~ z1tl!OsD#QR%K$eiDcw^b?!FUr7>V-O{C)13gL_KF04g`si69yjN;G4zBDQq*6)4S! z;t>5(Y3%|?!9w!SVBSquK0R5b3qDi9kGISdKe)Y zBadI($|yL*xtE^54!a_tAl(tWYVSIPJHCoG`(!1HkhPX|W;H&V^CT^_|-=zz#s5gbR&-9r#el3wmcc6RN;v{Wz^;esa< zV%ZCywJJEqreXkjX4Du<BE#K`9RT~U9gf)T!T%mTyQ9jGgYwUlspf4GOez;#| z`u5(acB_NoyuC}CwEH`1PSJd0tSwPimxA2^Pc}Fr>HUS$fgdw!I<;q+|I>MSX9+U} z*M72-YBM_6`BtBo@TSbk?rq(YNh05k$h?15>EnTW?SB7+8wHV58FOmxT#d`x#8w{}i9_rNL| zM~)<6Ou9Dr_ef{$-nn0sl4P>sEs0dc%a>Tw+@KGbbabTdw>1vZm~{H{)!5ii#i&uq z0|x~&GEP^1jc!u^wO!9om5~KTz}IeND|Ra06N~ayCBi^XZ#sH)O8FLc`#( z0&|yi8UcSNm;mfCYnlK8YxMsaeB=oMVn|LI);#0{Ovn|P7?S(_`#bg))9Vw_r;;`T zNNJH<+K|;UY20=M!16d1S7K77eawL{6JM5;q#WCzIdigej0t)Iz6ufR>s@>wUUU{NbRq`(q4AP|^e?wZ5IY?yhkNdjQ64bd)2e`XuQ9s0}r|oB2l6 z^@KaRxz&MCRqHquzn%|C0i6Fz3@tSsC!7EqADO84@zx37R77TGlYeEW>hyDyWfDjNq~pO5>?fqr#$>h9mS}TF-$72pUdX{ z?g|MaiLWkg$Kf^EZgP8=?>jK487y@VaB%v7m=RbOmd?irXe6Dde)zwmDE&9=rT-KE z6r?cmB8w?}@aPc@>cal%XluL7aHW%0wV~bOz=37s;9T(39i`IVBb?seZ!##SxTODo z@#+32THpUnf6EbKZIOdA0L1pC3#YI0j^Uv{55%hkZ~u$d!6tv%340{Iay`rLS_=ge28!(%{-k!!zV}9gkO9)SpqUu6HF70y;{p zF&?^&2din9ptSdC#tY~eNVfl8<@<9*+C#|#Q)6xiX7a{O>3WTyQ&@sjxhXjp%lLJo z_U4*o(mwIe;I&OJlY8tpQ>|8o9QI5!I!1m?=i0-Q<5ZC1;AV4YL9qWq^;+`Fug!mF z!qx3rmz6=!_(evA(41<+1rToVO8A_&>G@gjGXrrc8yv>ZAkm3&Q}zlq`b}Pyy7zhf zn|#pWjh64xyWPZMB6xz`#F)HNYIDE&YHqg@hmsk$9jbzaL zO(ynw8?@_*8}&x4*}0YKE6J%JJ-(n*omx!$0I_F#XHJk|kum!@t~T}3rogZ<>)KkQ zv*cBqNG)C}2%oEc_pM+Ug+M_Ot*E5bRPHf;4mzSS>BJNk) z6EJ+^l!8X%&jEV3gbeCW0HNvpqXuH1m>J*5*hnVe$`7kn9px<&+7PO9Q(R2lcy?kz z@at$jC2|G%%1sY<8{f+Ke0bigtAwY%uI>bP#EQQQ^a=KgYXiJHD#)Mc?AF(Os9_Um zxNiv~?U~cnF&e8J+5J72B^QJr{Fe)VHlMbLsjgPAUBW2E-`X9Q}R&?b&Sp%%NuU4WTRBe@!k6UGZ&qE;+*L=1!pS=F?~~*256;T97l@Z`6{;_Ig`34hhbgX=`g+*K(9)W@cU*V;Wwovs^Gip&frhHyj># zO>U33e&Z03aeuTO_)vH{B-meZ?O{g}`My#iufvU9_?llvMwCQo@(9jd$vC`&HZ`P# ze8u|}@!BmmbMl(I;G9~cnUJ}HHTh(zJG0m3^%_^-+ook`Bn78E)aNnW=( zbVX+-Jc9=nsi`tk@_t7hZ>`4F?`UhZ_Flf=1E50{l)FM6-M@b`-*A7Jw1t>QgT-Wf(o z8&m$JjrXpz7?miXCQAk_@b&Mrr%gMy{)Iiydo}ibf1|s8ZqwqY@qdnccQ${yyShMd zZ*RJacqVNS)H0UqJb#&<-jyF`NvR(a{wz_o`yu&!>KZMftusa6v{mz{$$sxTgdZo0 zlHY443S2v+GO!~gvtBgF^yTDxuWDY}?^En_>XU}ftTUrbv}u$J+0)?SM$X|XM`98T zlB7R>_z)}5@1MaqO2*Uwo}BRgB7AMR_5x3eoW|6W#ZM^@4j$V$bVNl?;}b$Wp<{Oi zmlu+CuckY^@4o@y_Gg(AVmCU(6=g!YjP>H*#dZ z1yvu9;NgmH+KIJoVArjoAT}~_SakkY(sq2iLk`;76~6ti1%kz^Xs3o<+p=#%2Ft&1 z?WS$@+lGREJHY@M!K8!E&W8qm5`45TkYg0;IRhB*OKZB5w^_-bs#!?g8uI6fRfAy% z`M*KuXJuA z7eS9B|6)N&Sj2sgT!bh)eyDdLUyXnIE4-o5E~NbahL{XZck-HlLCjHp+MR|OfbxkS zaKy>g(Q&~KVOZnm|L>O!X;A@T8bT*I4YVf5QR3_mxDh-zADTfVjIVg9wqj8fJXp@?9-~+G&D&RJx~B5 zjvhqj7}Y3IDut>*r-ng25(YvDB?^R1lC~h>G*MT76)~%yQhyg&H_;?TNw*PQSI*sx zwC5f#hJ1+T$7X4{@z0SF@0Ubl0Yc*Uzk$IGqYOyLlV>6I5!DcAP|4p1)*#eY^Xmvx zkUHVXkfI=jfS_Jgsi! zf#Lb_$|deL z-G{7|rbOIjsduLpHr$kPiX`6v6zu?RJD7oXQFiq}U7)cHn=eKn%LxJ-Aa=M>zn&pN zAq;d>MI@{wL8_Q|{%UzNo+_$s=#-P;fy2BZ9dE6!CW&Fpfzr|yRxy_Bd;8kH5d^^T za(07zppvQKPssZ1kcL!tAHZM2VVA+aC3RpT52kR+zd?hJ!e0Cif3g~FJK&|R@k$Uq zAm}m{kKGy~RV+2y5>^{Wi`vlLU0U5D6Vp(6{QWNS*zM&KnHgz!tyv761@X;}_*0jZ8xzx--m zvPvlxT2P=ElSN12$@*A*^nilvL0#c*P*5kX3KFmt;iY|{%@34#D#4c3j3<2!g0aNP zq%00+?Uqd!slF&Sp>6U26%6KozfMABOatm)iFyPBOw5!Mbicl%?JfStZlHMp*|5Mc zUNcM2>!jQQg!jK|iC58GcZIM)iGG8Z*ACmo_w*Z~Nl9S?{7Q$&ML&H0bMwDvWKsj= zFAOIyKl~}|Nh@UhV~+0usK+jjP3Z?n0b|q{*_cR$1vP4XINRcl7x>`IB(Ot~t4GrO z@9HhyUc6J40jdDIW~`gS2GT8l>fW<=liuQUl+Xi^JxO0gUGqK`oT=Z)IzK)jA2?}G ztD{rOa{COP7%`)?Il@butf$=0&D*%_(a~ujF5D2y`8QlsKG^LBP1o-NyM?eyi5@oy zos10r8hfz&`s~cS{5BJsIm8x)Xr!>x#&Ng`5@Rng{fP%i|1#P}&Eu5+1CsE}Fi8>S2pR&b? zmJDGZ3}axJ3`*fMfAUKnpd*GSM~<$M|58)curL|fE~1=G%shy!qwe~pk)61oyL~DY&pu#r6UZXMSSH{np=Az6)W3^+49#$WDK7C2-v?uU9Jbeh zkA_Gst`H$8UJ-eO;RGB;G_xoeJv-(ls4c$Cq`U6Tn}ewI|Gx{1+%Jblc_JacJbemf z6pSAEUBhNnp)i1q0he#Y$KN}7Vc_udA2*$`GH`sUv)A6i;TT@SG5Bx9`M;q6C zF6cq6lDlOs?K+~ND-bVHb7N~$&?=RCAZ`46-kmC}dcr8oQW-P#0K!Rz?;hD`7B4l`nPT(9gu;ZHo9M-8kNwD zLMUlyV(AA%Pl!UNRsanEF)%@SrMi$FlZ957Aail?sZ*9|Eo0M1G+@0j)8aW+CqMRY zctwN59jH8&T7oE$Zb6BRas zqxXEX#_ZpqG==xy4$}m6h;U=#ipPbDAJJwrB#+KLfq(_g2*$ubWbsBb!BQ^sr>6QZ-haV|#N(N5e237|96)!z0g(28)8z6S4P@6sp;)*$ zxli%cI_AOZMUNWBY-ZsWLYt78ng7Nw>GI%m%;i5ghIPe{L!%Fhy{E$K; z&hcm(J6+g9nvxn zhGn!32Uc+By5M&+^m6hi05I39%1`jo=Ji|jy|XZ6y#Dp4>SSB`4!6&&HOV4Ug>;WY z8q_<=&M9poql&{uiuOF=wAYrAk^kD(o(&m(Cuv(GZ&Ra8Y<%`pZ z*=?vT0^cKBG!b6!#>oZRlt>t*1x5$Zfn{O{ST(KT(PSjL<|wEe%sC-;#Oaj*fG0}axK~X)ZR+cLz?c&= zfYy57Of=XS=rsrj9GcfVOoVh>>vf@kjK@T1PiWL=tc(E& zj8H8`|IP)|Yl@wAb^X06jGm6V4`(+aW(87YO4@S>hpGgA(UM;Khnt|@LPA16h?x@g zcmTVh@vM~qy2PXxj3s6PT_2T{`4OH4BXlBU{wVHBy9&_( zV&4leC=tnVwpofj6|_`wPFA9G%t#v;3OcaTK)eU@mh}N-UkDWF#vAQ(zI8Q2g%optRw^I*g{JJ>HOp2L8MKw%{|#(d~b&-rU2UBMym58QBEErAI_N~5=MN0 zSxsF^wIv~cIXPX>FpgnMk)niXz){p!D5ZYgfeK~FIbn`5G0-DycKf9(1DFQlFXX4t zbqG`Qr@XROLG=Si5>)8#t)IR^KUHXpOQbY~?WPd(#M8KBL7LLqxygvz# z^``SfTv4sBk_7`Xc6GRZg@^C5t^>1n4N$#20ys<4EXvra9 zXS+WW$N>pCZzrUaUQGIZsk|4I>HB@iHxqunf5F?4?rb~OXif8_Xu&D7|j9sDSy<$-9VL5abQF$KLsDvXqTCaYvd z9D&&7%Qjp93>+u%8jeU-8!p=8IkXsM*jk#!XCKa&aJ@SLMLrZA??J8zK_)Vg<#t?x zAkadP3LBJ(wKY!wZK}^7hGg4XNh@8d?Py~AtnhE1&28A502De7YZ@W}c{_e7J{)(C zs|G`-vw@?O<4CnA9q)1I`T7uH98^H4<ii5^WgKd6N%_v!qW*{d}fDB5c;cwG%XGjlw^cyV;81Ph{v9uvg*NAO$Mr4As9tX zxs81js*^~JbCIo3>@Owg3L{e43_K6o|5s|hxdw=xS7oE8E@bL=YZS~rPyQ>WM~%5ta$ARXnHYHc(Kj%Xeded@ekF7v1e_n5f_u zH4-$S;)4Dy)bT(F;3fCj!JbgNy8fgFYXJy%H1SbeDoe=t2NQ#;-Z8efLeOGunVA^4 zjtvrdlvd&0tG1k&duV1iCM%yW(84C|KWT1!>H78|=e>t#E|{CtY~S(7I!!0}dPv{P z{ukuz$ZN&q$5AnkF`$+^km~|n30pNWjl&j>>q4xCFs-g5jv zb=gVr!s*0Zhy7JjhaL2`Ue7vyNB585^vt9fM?9~%CL{<}TYB|eXJiuwZqC@rNkm;2 zNGy7YnZh#>-c0cgWn$p2rxN-UoJuRwF=cs+;|HtU>#goQxziq(HR@=-`m{>hniY92 z39{}7+P3VvHdL!3#=)zk8G<4ViTgC;XXhtN%!t^UZnPS2s`B|i_W<$0>4TgzSo(l` zp<^B?`e0+h1~__@1<$rz&iT1^)s=R`;{)vO-Su%*KjyzKT(NytmHZ_mcywS*5@+p0K)qhMd3~=EkD3hrv1+wgT&u|J~ zPI_Y|<~edmNcO8ZzAUuLr$M#C{&bc3hs{n6tC_SSYg8Ne6@=}<_66vj5atISG5Fj1 z)FwerRv4C;-~)-cI8+Cj9at95kjfF3NyMooj}K8!tUrKfwDq*c^T0OS5T7GSmgT>> zTM~rN{<^i-a`Zx>l6>W0by99hqTw@*KZAv%D>fOQnq{>WxV>FoeoSpf>iEf%PWu+t zOF@qpXAqKakQua=-~DOT;An!gks-hzNHtAfwd^%zr3XuVoc`2U<{i3k_CzerBO$vg zS_EU@XIhXKYujt{l58|I=6(%=f z!rOCZCQQ}kW?rv4;F+Z>m+#~BDVpOulzE89ctV|H86^lCxAIu649m!truCkf;h3BV zl88Ela7?&irW%ULMD&ZuHQU<KJTFh#&{5erdY&P}KYv5rHfsLN%lu z`5krF&!X$1wOPkkoz~M__VFkD+=HB>g~SXZzd9CfJ{f)f&k3?h?G5%Hb=Q2QQ!J)2 z^(n7ctgwgvj)eDqT=4p}+L{~UumGaJWMctvjIXSb_c(~FO7NKYXqH8E7R$N`ISm>I z6#fV;EiEE8Gwq{-6)1B^VU0Yrk8ti_$q~UAtx|Qqh~35TC{-QL%@z~N73{e%dgb98 zKIgsR8<;NlB+uuOdb&UKO$?Zmwj$8(MHHz)t>WVBkXgY|7T>Ly zXK>`Ab&PDCz-7h13=3wVwePmKN;_XSd}i_cxomE)T+QIS*ueQo7XGH?r;J#4j2?wp_u%N>dg#d>gp}BI!K)&&;mrIDq%(mM zE{GAuq#oQY4M7oH3*=>u5p)TYNn~_%H0kZiqKvCUU(XNZ>E5{f;<|ioZb67b3HzF5tK&zcYOE2r8p^}B-c)Ey3-8*<5^?Lt=F6vV#PSzr zoix*E^_0#Yc|0$su;X_0uZ8;!FY8BH4K3tQp#ZM_+Qris8{idSnXJkw1kQpdiuy9Q zRdy3;On|BHVhRhemS-1m^Uc238z?uw;yGuexbu5-5W-J%xRu_5iI?qf@^+WdZh{uu8)?f7DY*H*GCb(BBy3A$Jy ze5wlH0(TFr^G2l70L~}y-Y$o`ED1#(cs5o8CAs_ zN6+NMoG`^U(r+@;q!-E2>UcmL+w$sx-`52E(zb*bUejQSoZOejYi7&3tu?0m=7s8^ z2Xp^}1$fbT!^hy^f7g5KJva2)o~|)}GX8R-j<)w2&hI-63eJg}X2Z)u0>=@6hy)}a z7$yzi9$~OTB8_;uF%+`?ix)xvEAdl}%EZDlWqKLJHQ;Szyys8tj%(Xi)c@JWnqZk{ zUw<W_Hm9FJut z&Mz;eO~f@mCMG*ZdoXN3HaNxmbc$8l2O&Q(=eL3i$7|=kNtFqh3tTn>fiM*uJSudX-w(7ahZ*H``qfPZEp1qbD1NG>Rf9tVh?oZ z*mCXspUvcCz6PJLPCSNtSKDiBhYHvl7Qcu|+aB;Dl_|yDj@dvyUZDo)LVS zD?j``DY;KW=P&sqwB;{QALst#`M{##|$nu!eIWF3|T~6KihW%?BBo ze`CGhbh&rSRoUzD#@6(Q;G{D5B(WFM+~}>=`kRM*YJYyr>Nz9Bq-a5uvVqiQ(`4NN zG%HCfK??w^lv;VGEj>Y(ls%vxK^)1Lf_!`fG&u7Z((i76w!pN$nGy4LA4|)#-v49I zdtqOH;zsK&F{U||h?MAq-AWVp6Um|eF!qh}_5BNL%$uq+?d1>6>bzZxg*7JY+r27# zYxzYehV(7Bo?=iBZn!L2d=JQes%At&Qql*^V&dU|xq%%|qfiqiFGyd%hdW*O*y9)_ ztSNDh_nJdmddWU!f0De|9@~c5#@o9&)g(9Zn!Q;Udob_Nv)V%m8^u_r->w-SExK3Z zeWbuq?D20L=X1rYt8dgKm99L|BqpVjnzwO5lR9-3IXo$ZYsOFcs3^~kH%0iAKf?MY zwFLx{Mpjmv0xU?U0(!O1;HhwJ+$co0-D`fK`>gt!g{byC zL*aiXuV;;}HE&XuZna?1XBF>0vde$DZGCc9_m5?<&xeg#PyeWTq(E_4dhSL0waLE2 zi~*|(`!f@vNu*A-b%$XKXbQ=^ovBkLXzmfYQ%vj)D^(^XLTY-9!CN4S2;y=wVKOnu zf1cEw_0AvMu|nG1lFch#*f}u!n1lP;XVsRcFRtF36D?b~C$u#a0ifK-RFm`xx5@*) zFO3hEq?bQejgh@`&U=$$pn<1rOHMbp(jMxRKd`$bbBYO{v@3wb|3HU&TigiA*APO3 zkdCsrN`M6eswBW?p%!;9Kkim1;s>w!XsaupFGcg5Z)6|qVe=~z*3Naw`>$tTTW!c{A5@xMWw`s8uGij z`>qMxRS%WjJAaBRwDzHSu2bCsjp+&ZmbU3O{r{NzS(t?DPY$wWaev^kR`2%reV35rLFpI=jT1Dj{q-#w1$%A4O#p}7lY&$OJTq?d~|EwnY%a-%M&$qu_Ci3oh zXLP=X z`03iIlL*n!*{ZrTdJbzUvhvY(g4A6|uLXqc4upH`<<6&@Z6BLga&`2@&~m<FxP{ZeiV(&No`G|J%aKp8P1c-xr%T za|RoHGRC9&TD(a3Noj#r`}Q+ee)$FP4)YN^xN9-%>sH0VqFQ-jc8oC~ig=NuY$$+s z4bmg6<&qk(bH=*GbqJTFNUCFna4$yKm$L8Q>8;Tj+{PMH``ZQafA@b=fvcTOYi^i} zFaJXfIu3?s3O>t;&DhnSbr~ zH8)N9E-Na!TIE;$jFo+$`>xEi(D}EaM(fkuOb%2g)@)EsH|*#<^G$k( zanD2Z2eiUM=W@5}4%y7!7iEk3{n!{)xB8;*`f?Xg z9b(!W9$x#tkcxyIEf>2CDo0tt?CTvnZa-eKV8++Jqcv}!%U!d^-r&a8^h58iIglJC zGH`dU;Ez2lVhU}NAu3*prw?mAy>|1r$ zr}g)B4|KtZ8ySURoddjqu~jY>rmt7o^T*alLopG87?9owF{ZHCD&16ic^Hc`7T@gH zl0CJeOv+wAUg&(Yg;1=u9bBd)e3tumZ#fc1=zqR!2f_ibZa8G#kmlsT6QiBO1!;A;FmjE*hzfN>SyC_PrM4 z_)rtqJLTy)Vjg_I@W%gMDG%_8 z6n|Ktf%dfk%tN{oP~*`r8TPzV^ta>=@2V}k2NP+#Bp+H21OgEzMPOj4>8RUOC&BiR zSjvtAQe&!;5~Zf{8tHKL${K75FAU%3hTm`Jy1|Fki&VP|*DT z!v06%e+uXzt`Y+>#!)eVBg~3N*AO_uQcUJ|XB|`Yl@|`&`Z8T(@Xd`q?DvZxe_?%> zD>q+HoKsS=c3ujK6PrdnYFMioGV4HF87F#i-q0x9zGH_DZ%Qe;qX1(Z*|n)wLGF6E zW?HInE4n z6Z(>UT<7Z+z8OR^sZ}vUT5ldhvx1mNfd;!Dp$2viVrYqSvm5{2_b8*&{J3m!Z+BL3 z%TXB}%i)gvFBAF?peLs&Urp3>fdV2MP8r&o*8+X@Hhf8~D*l!0R3B6ILzrFjY2IPq z|4Kjg-&1JDDUY7bh2fN@rlzOR&qgdt5>B)qx`Oos)`**e>luZ97cg!_)sUG%=0E7n z080y25JFWYyPpO`uzzTBtQb};3tLb94%T{M6@a@W3s~hDOh*g*w z*~F#XHJsY#^6%|v!$h!Xd?JLZ0EnT)_5tB2@v)gTh=%?8Vb{VC-m<|~r<9LR0gA~lfVnSxwxl~6(XJ3EI?cHAa=o2#&o6~G1 zH)3h+H;=hO(?Egl%9WGf19~|zK)_mpot4|`Ic9K%LD$1@{(`CKo}cpUGR*v)wQFs<|*m0mm(53A{5OKueiE zbY^6rMp%6>cVFYDS7!ElTVsT_#i>zEW9DvgedAXC@)?vh3ji-n7M8WRm;!2q-qsd$ zVUv@S3%*68MbU~3Smk7-)Oj4^>z`_Qd~2WbAu2_fG-xWpFRt_F#EWmPDE`vEX*v7o zmE(gQ;w;|F+72H+noDIVvl}d3_*fqPz{oAz&ee>!i3=hri=yklhNHYiIswc+s8_24|GFGjfEJwAes|xlDv>zs z9a8K1?Bv^8?$$ptOz(DA9N~mQoF@vc^_4?F_!y#Hj_$Mv(8|b%%IjnwgT7ht*HN_* z*xKDFj`2}6x8k0Ox-8BT44eDTt}ZqU;TRoYAOJw_Uvuj0~woP$Nzrf19eoE#mASQ{d19I%nC{b~U489O)#Vc1xf29Xx| zn#n|NzB7yr^f>tU0jPlp+zis_x+PXIRf0HwaO>`)n4LmjDY~rA*uca(Vz!=-WDRQ2 z&`oK0*M4-=!$Wu9dA~Uu1s;DF_%e=-5!FOMg*GaCZ~x)?8D#VOsK>T#umz`)jgYt* z1L9?*q*5^jQ7J%NQZarMG%tztU@UL<;O(vXyV`!|JJe)Hw|z7<#+HKeJ&s%=jFob?T_p^zhl!|_j|A3)DNZybj z;{*T-&-IpaV4LAs_Bv4@LRds(V!X*<%*MGq#72s^eEj^Zh7yD4^>2C4XYI@%i!;g-5achSZffT^!1EsgRr)2tJC(>=jIRUM)o5~X zYhJ5TmtsL@7xerp9i_t*Ni-5;pt3&Z4WYbZCrGk4q->Mbpic=^oL9XyKeuEwMOllt zASp|Sy+ZN!kE3~cdFjV*=|Ik5li#e{h3Oh=Q*UpNY})ImGNpB2N5vlzd~e)7vak7-Q%(mE!yWLz&Zr%f4;mIUvXaq$%ayK(!>iNq><;$Qi&pp!+%`0UxUnh#eU ze(CL59@l(O9u8@w1Hu?k(9+r}1`YxellXJW06Dt2=wj6*Sy;?ofTio0F6y4e?cdTH z<|L_0CE_Qie%#w>6;;7Lk)U`>p9aHzwaPaYE)`lIBE8Y^^*O(ho+QDBVdgykg5=7H zE!~kH6KEfvHpaReXP$n$ef(XN=Z}vS9Gn9pRG&W+tK&b|TaPQP6N4{E=9y%uv^S*8 zwWjpHXrFrsn3+IlJb#Zu=f;6$0jti>Pxr#+_ig;St$B`h#&B#DS%XI{IrMnN&WSIo zE!g@gOHz*Ko_wJZP=(|AAm_$eK_JiwJd)r?36wyC0=`X3$GVcK5TvNw>^UJu8kh+J zfiVJHJ_FiZQ?Jh=CtXcZnSY}$*|b~W*93t!&wOqv&IB*LZffYP!Um&}Jy8ecvFcGp zWoH~_14vEvZ)?5B;KA{shi&iQQ;lkv)c7u2jqqK)XH$F=`k#1xY2+w9dEG zf;~ij6_=VmwzS=)88Hd~h&AEJVAxK{NblfZ=uj`*?8+a(DW5y1+O5j1T<`WAiyF<_ zitxW2K=*-81EEZqR^vcU9yR_xHvI%WXyRp!up6n-_w|QN1|dXoDBpFXI^DWsfa3x5 zLWo7xT|65%e#GVPhz8bNn(?iEjd?-5Q5k2iV$=Pq`Inb&SZbN8o(tgNaLmK`Lvk`e z+#snV%5n4aX(iM^A+cqKpv4$s5@^XW`(DaMScu(=k=`N@j~&lKt7qK-pi2SQ`XPwu zu#$~sre}+bP#EWr%0x-02IFb%NO7svtxfxZ*zrKo=yan*V4b50Oi>YC6U%7S-}R@5 zI5%x-#u-dfG|W!1ZQG(dB%5Gbnu^*trspewkpY&2Khxkn#WP3^NU#ci4?8mpAAgWv z!C`dGq_>g zA5(PGGoNTu!~*1NHRGxEL@xxH-0q%rCJ6aqaVbjs#>mo2w?e0OiEurE&OqC1Cz@S= z8@LguGW~8aMk9Kg@nZlslY``U1H}QatN&04z!1WhR=>Y~)zYAy=Y~^Bh3@I0*64A5 zAk_3pSDDfw4g3P^z))Y;{Ps8sj+wZ$Bu%V@9oVJOZQ8nTwSbJ<$K`d;CY#sYuu3mI znt}|Hy>pXdf&T9946N~VKnbBOZjOV2abbt= zl~0Ew|Nh2)#nBLe+$ZVLa|o+sBV?^2F4owvbjzzHS(v_ zUX2X9cx;2<7S!6}*roO4dBEFw-g!x!gLNr*U@|=eEu>w2;)@)?5+LS4VkR(UKp1s% z03-`hY*-?qqM)@R{d2ypsN}IOFSUay0ukV$_hxP?*EF+*P7k%nLEE` zG^)ODsO0B=SqD`W>IjTGD@zvWF~B8%f`4c-uLvyK6DUmKF+URM7x@HS7GP(4sihn` zkWPAjEFGsjB&P?rvtoAY?U6p*U3o(I(m6-Y+)T5|174Q}cVV*;+b+{?^AO21s0B$u z>pMJlqVb%AdHx@^On9W@YsiTLGT~ulzesKEv>V4D(5^@GDU=H7A$UTgvtN<2Ic?pB zC#W?4eN&-R&NW+UcC8}6(wh$eQP`a362j26WOS9@&_z=esR>shFvS+2DF7#pkfKHM zsH*e~eAf71sN`uMl{13ZiJb!im59r$;`zzJA=_fX?wNQ9iGM$O5yZhZta3GrZsoOj zN$2MmrFeA^9s#8xhI8oHHxKX&^a1x~+$4-P!J(pakIBr0wbsZ&%1gzl$e${MB?}1+ z#c3M@g4HN|e8G%+Zi*+?*_eEJ+%@%Sgsb98UV-aujh&O*aS^%7I-SJrCq6f+oX~ei zaVn9>7q30SD!248r96{~dWcP9IfbfW_vGEotZkh2+LNDdHhfK(9NQK+f&`eiWy|(&JIi2@hc0y@d)VZ{N-f6t z%>s2fs~P5J?=tL=*f7~I16fM;F^;^0Td)@sc)JHQ8R1;x+L-d%HGg2TWZ@+_&qKQ< zyC6|-anyemI%dMVBS#%l+tQTN&xS zZXI#AQ25@|YcrR+qZW!met+}*h_<3Jwu_kgDWGPFGaL3vqDAFwXUBhU^vHA34n_UD zO|h!NMij&eYTU=#M7@+5**b;aZM@#nHQIl=8%fHOaQrVVtSuhBobyMjeU;xm-2Lg2l;ZPWR?u;jsRH;c8caDSpywjN{uAt| zRkM$BA<^`4Gcw7a&%U^tfa#o}T7d^XL2NA+X6qMRs&6q0-OtOD>B}r-;Lu(Mn!?U*);`mmKmO@R6j55mh=D*t=mNx<1KnQ#S&dI^Z4&uk>fV4Ov;gvP zghA#fGNqn>ca)1`mW{l8Wpt;uXmC6S!gN}?N2o>!kML25Fo_oCcskGA9_*E??j3P@ zE~>`oqY9)9%zToRFw>`!;y(NMo_1%v;nuv$E?4zaw&~Wx&veO(L3=z63I{rVk*9m# z^%E+F@1MLBrrPa#a61+a<_Y#h5u$ASCkx>xQ{KB00L)F%<2XPgs)`-OQ zAut)&)Ia{^F}PjBJb4e_90{i4ldAWOX{D@V(pAP&+FXlpzkTYh{J7tI{eqFHX>+%A z3x*A7BrdyL1x5Hw9)bbEBQWuV=SG$-TQ)&DI;t}bQ7~`o%j+VrYWPbir1_`Bdj?-U)`KVS z5t>-Qv|H-*%H$j8$8Q^?2uMoSiwwM>DuGM;5KRD5;3r%hpV8ezh(KtpqPZ_6bBRDw z<4Y1GSf=94wJBm`6g`CBZMyD!?=o-T#H_R>2fZL{h@j$i03rmSjt#`<37}>>5tA~j zSu#J7BjTwU)qmUH&rMYoRH~8@cU0y1La4qAx6c9-MdW4)DPQxdG?{hLMVR(u7V)o z=6J=~LJNWfN1}5VaHFv!L&P{#Q7FHVPGh|@?b9l|I2-!z|6*jb-*91K^tp)7%!X{9 za{Ef)`iasn;rx=aaE9tUY3KkZgjtF*s>RqkIppp06~DMagqwBA2tSto%5iqkHbr$= z)9!5vDAa*;Wq>&|a}7vEJUtYAvlpgQ78+D%U#o&&-7m0!slhP6X8rnOpShc4$duNt z@tTg^(92EX4}+_=qdgiHs3sGv2Vum(NK<5P2UrCYJPRW{GjM1+i}=Q`BgM1O0zl~A zayno89}VhcUzB=ktHm4?dLEMfH5*kfL_#b!pSKA5;#{hbQxchw|77ifJ#!@3? zpOGlPY*K?ko_VfbwFzaIi?3fX)6Z7cDn=MnMtsY{=^Uke9rM2)S;BHzhmSR8Y@)7D zsCiYHDilOLD>j}z3ZE6y==KCm$4e<$XKwTiGCj00N$&q1%X>z|T8qpeo`Gd-Am#*% zol};$^2|jz%tmzb<+3?r3ca5WxGcRYlRGXf{B4IfS5<~;aZOJns!lrtjXZuH z9{UNc0<)8Fwp&|u`utNKhhm-DuoP-b9?y2>QIC)BGR{)!+J(mj+Yfk{Tz<68fncVG ze0mj$kni>A=xzN`swlIpvpQ#MeD^LxD!GjKvOQy2!8UgDpDaDvioCLUG}R8~+K2lN z2l4a;EZg+{$+0HDJ{TO6rCG3jZV2hLcwiB9i_zA&>#Hk6+8;jWr$k=&zwB(n<9P^y zJPmr?2sYG!0_dc^)@~KmomTJOaDB{9AcV>%CM|7DP!_uG=e zxmeGtS5!T|w!H9=m$F2PinfQx6Tlsrx#`8Be+!UkO7ew2=7iBqv5}@dL&h@ho2U1u z-+jg&Ts75ohMj03e60S$#b6D+=3+1c2T=BsNdN2~{)jv+UNu(v$AuBCQ(d9sK956N zyU~^eY5%=h$;<(=IjQ;6RZ#c>jTG2QBXE;9`?5?vMBE9s4IOhBx?a<^kB_mf0(~Q* zaX~1Cq%+^q0X7?bm~1dbD}q|~M2k~s`wG9WuKaLv1Bz7GC4O>A>+z3-e?KwMGVo4u z2(Cb^c!!{pk_F~32YFCx+nS%6{ci9Ll%gkZ1*3W*h{6K>Wtw6MCOZT@jlO@^{Xx$V zkZ|`hHhM;psKWwV6DwcEu|=)=x%XSn_A@glb}akc?P*{!b_7#XFDYwc+PSX2zBib! zuh@qiWFH|lAd*-o3@8h?J(!&>EIZG)*p7gILc9#7wzc>U4T^4x=ku@`Ky5ws30 zl&H>FZ(+GyZ>VV;S;p=pt|X?-7M`~zIbOioqw~BwOSfYY+WlzLrN9j~?6J%^x z$e&21&OD$NtJara-LNjQ#_fASyR{P<0}wz~u%)a=sd@%s@I6AR<(7Bdzi;32G&+^H zTpEnx&D64S>|EVNU)8BGwVrnl|BhasdG3Mky50A%e?BW7xpK14+4}EI$iq+=Q>n$0 zWHZ+^>{`naGjvF6*bi$gH^7m0!ZIb8_Zez&G3l|_mfEWr>e<&;1jH?!?Eg_*`Yp%Fn!x=J<}M64zU(*sW$kEqQU-RZNHSbj0c=VOPJeFUfxV4$?C5wYk1hN=kT3sbF|yWHX8RurQsc zM|*M)O?%TZ9_C|2TrTD!G3Hh?eigx@-pC=`b3qB0R26^)6NU8`^i`)`t=eyFtifCQ zBG7i%dfHUj<7T12*Q>^@ZjpZ0^^0xfDps71#WBFm5RQ8L{GWV~8Tav0ymZ$yg;1sV zw3t=3_>`QJCxU>5O_D0DfP%uruaka<{l?_|(owNwP_MKj^SU%xOYsbjd126pZ>(^D z8N>RgbhAg%-kKrZf@M5DhEQ%7paySfrfug}TVx+LJbM5hU*Vur&$ASnH_o?YoG=LV zetx!(4w0HF$x)h8=AZQEcPx9zB!GB`L0Go2NZrw#UH)V3cFWi=dUPft*sD`!KHMc_ zAa2(JbvU2~2c}kVVZ)-2akuPmI5%V)hg7dI`M zvU(HtBH1_l;J0#Qj+d&2;^G7nTyt>3IaHgGD_{dGm1#Sz_WQd^;1u1v068z=P~DM3 zy&#Lh%0Zut>c1eD0ws$J6Is>=936!N{53djXy1@lGthuA)qN_pvDU+gF2){!DT2fq zpRV__B5bk1)Y8T4Kj(`Mbtq^eh)y`>ja|e4y(5=?h?hoCXXBnc!guACZz6A7 zP|L5YU9;Ox7ulLWK)R$$LPSJid1Q`3mqZM+$k1lz+RH+su6bp&bkJ+)YaoN)J8U~e zt{26u2H;l7v1ZL1oh7=$aNQ#w52R%MS_**?g(;Jbo12@XWeb_jhCUL>v17)|)o0gd zUS=4EO9ID*@5`;I2H5-;!(w4DgDe@kRKWrHPocg1u$F0ntmzWz|_~mTf z)KW6<3CIjPh2fBti|7(O)U#JS2d_GHvZxo;bUmtZyZ>>+NmJ7-L9%(r6fj=$RSm!)b>$Z>Oi?_RoKIsuwwTx;*Hfi0^#r=;XBQ&23*gziPY3fYS8C z2C)e%^R;UvMd6jS#vZbroNK{AG{y3!tSdW>hehSYJSFTdGSwibZK|osn8wR1MecxV zZ}BIOYe;zy)o#~%x&Wl!S_H;VG6_iYTA7MlACP)_a2NT@V6B@4Od;nB3?7Or|2UVP zd#KfLDPe7}VW8nL9L+Y6HyLK*-xw7&dA|PxGVZ<@H7|raT zkZs%@6W zt4Ym!a&~%2ihKDOZFa(DmzJAB58N6hJw}FCm?Uk&oRYHTYKs*1^pkdD!Jx8;E4zi|8B=LybfMs z9$^0y-DtRU*lQb4G1B7w!1yua%Ny1i7*m#TrU%if=)y(>z994jXmlvoo;kp#5n53s zgjRdR&HUI%Bd6ki_}Gd}ua{`(T4d0vT!TgQK!Y~V$Fs#_8+~=lGQuJw9lO`#`22Lm z^LMP1kEnfQi(8tJRZD@GRTkDsk=Izk9(s!yA`yZo_~A&DawaP3Xy`q&F;^9(9S_6v zC$GBR)jDLoJfTar$)lmRwl;M}YH5cxQgqsSM6Zz4`PEL<1s=PI4jOt*%Q%m<3VJDX zl+nHZB~0hjDY?@$3;p{{5+%u`Oh+ItXJ+DAueui@YA^*6!k~z+NX}`&dr?hYoYCne zRoinACD94*gS2g?9CU~L4QW?E*EX>6V|sY;PQCGuI?ERHqMO#eRCF&mWb4*X|2J3U-NtPP zYN38N@A&wjJ!dGY>cH;Zfxb8q#3up5KiII2yQkpO zy|mX0QT$D7MQ6Ubb0%Ni%~!NEVkHAmoBv`K?+F5|-MwtprtW>7Va%BjU<{!S%V_)M zp|<+my}S3)o&-P7ZYd?VXYJOPPY*x&dgO=ss$G1H)ICJr2C1nf^Iaa^T=BD`vKl?z`i=GuQ3S z^%<=298ZaDIhK5)X>4q)kdrQ63u5QQ;TwUVKJht#>LIdYbt!e;PjV#wM~I>M_4NfV zl@Y}iDO0z~Iy0>|?ubY#?z>s@9cR4B#`7S{tfQlA`k#0SMkB;^o6v>9$Kj_akOA$lFN1WWtpAH8s*+w?wr?+_|3DC@7F!?g^xr(04d!WOQaq^wMu!a zBj`C=;lLnh!6PEV5b9td)KbCguN(Gp9h(W#x;fA5?2&8tBisA#hIa=yn=iP3f6=mI zv-W~c(*`8s^o*#zu@XE1@Q&}{X9E=)by4BhE7S3yDMyn>Y7kjwMBmWM)e_q5{jU0K z_4it7^X#G7rsTe?I3-u;{OCqQ{^bIE$xMOvBJ~j{ys%%=p&e9oW3jKp`K~;3Z8$ox z)?9#{L-~A&ox7=XQLq2~NR%Xb55nQ&AZp{}NkDqV6ApVJh722MvrWorhsP(`&-0;L zU)rTU4(J;gm>C&O(=l$fWyQ+vsi$bqkh`fym@iF>em4m^$@<=&5nf^e=={S_L2 z8g%|=kr5n&69Hk9VW$RAa*wD91WvH3OAScjlAdlp>|bOB+6IA)5tt}ic9gdUFt+7D zLc6`9Yvi25eKI^?voMtYT^Eyh^8aD(O`vk#-@o6xfo_D%a|21(5}`~@GDIYqHAsep z28tvVQkiGUOew=Qvn5KxHgDsWp;ViYP$;F8^SbWr|L=L$I_tmAI?p-hIj!Gs?Y-+B zzTeOH^SOri^}gO$>I4~cL~&Fa9qIO1`nj9W&~+ozTiPm|J0U?M(jsaKy-_1YbWR}4 zNRJck4y~*4BEU%%^6F29?V-?fg+P~Dw7l!P!m3Y&)Od&JTmF_K3-u!$N8$HThA$i^ zRuZklV;?@uR*#)}xtHw?Re-4ZJI@_81Y|%%w8e&&rk3_s35U_byxyMh&eneX^yzPc zrzlLvAXal`R)&cb&l!*keeU-)YT>hxzl7j>fEL?MJQr4c!=rq|7{|Q~+d7!=x=-tR z%-&qqs19-vX|GFyX*)~25>>x|ktt9&oT=AQyHRQ>EZdTv<7>UqMd+K#@dg5kjA@fvED#*Kdb{P~WXzo0g&lDTVtY(#h14PhINR?! z1Txx(hX?<8{kkBq>dJc15T78XByEWhESbpWB;;ZZgG_$pzC z&qJ`NrEh{%vA^|w|MM;^t_voMsA*pdnNk`mWbgoNXkWpeWNUURks{&J17@h_XIH> z=F4!?!sJ(L`!4mKkd6|T1n!E<_g;N|2iPo!0>6t=luS|v1xr^W|J2nz#@UhjLZe2F zpd!}#-o~D`w~~Cvus#RZ&V(K&G|{D6T*(JNOz z1a%TI5E_%Hwl1IDl$;9%%Q^QK8~uVetxdlM^^>MTdMXpZOF_wQO+P&oM9-mPjc_Y7 z7DuMK$q-`U^?&>JZT)R#fv>HjX0RNQB7-aN3+XL^*2t}FpjN?JBMM?|p(q-RKMe#M zokg*qxn_T}<8HKGgdzhV_0spEhD5w@ZFybH>5t>G>-q!^71azZs*#b=W{A)1Db{1b zw5d}?_fPsS8PCAqmR7}3W)wJ0VnT&ZCq#nbiZIB;M3@GzKFbx zM-lJwT-t5B-Q>*m3uxbv^bpX|{yVGmQ!q+Bg(JjH ziC_-gU?EPt`mCAd|B`(%l*Hh$XUi5X1TIi2GSXjtre@}dT+VYE(M;Sf9t2bUn4nn8d<&hPiU?6n{^f+@J#Onu_(4;6q_s4$9%^F zg>nKmOI#4{L8O&=WRKchks;WKo9yjt&JI<@YH8ab%LLH2E2bP06h~aB@Z-lf&s8W} zP*a0~A!BJ6r55<+P78VloiBb%O0p1zM4R&?GJVd;G;Wu@Jd*I^wEph03affQy$1zM z35ZBKpRKNGedEN$qqpwf{hI-C5W^p5Wwj~lyKyW0U7A&F7Fw!ernJVgnlw?+Dk5{L zIR(Aq)O1GSRD|kI7Yuxj!{^SKPj)YuVfnSi@I99OjqhE-6j#4}H1w_eBt9~a4Z5zJ zI|w@~*Q{yZT4B?b{F5lZ|^D%EQeS$P^3Mc zcOgqA7eVSc#_5uQ>2Q%DgUueKp>IsZ@JOrkA7B7Wl{PXes5?6I%=*(+XHNgBMeBMrmmP-5DjaLnOAxfeF%7m*IKU3|!Un5GLA7lwK55(S zl6_%ai9#d}^tn{|ZT-&v{t#X$@%gFcru=jjQ9I9u3aDPad$U1_B%N(-)hW%KMetCj zXAuA_x;JSIr~%r#nCxE{+G^AlFFnpq95a5rF(w98>(kC170v|| zXo&(LqIb1lNd;US)WnIm&MdSS(MV>zjWcOXWT*&}nh%F+D@;JT6@DMvd7pxy%%JT~ zr9%HqZ#n_cM1iI@mWTl&BU)H6+6P!DbTr8=41fm}Wqw#%c7@n5syc)f{ErdfBP^=5 z>i7M_;GgHofkz-_9cFY35Y-`C*4Th)Q!l!Wjh4+-rYVFw;iEB(Yz!l=wD0_jnJU!Lhg3o z6uLxd4SBG;{~}=S1ma*+ok&vB)zA;c9*2*7kez*8>LZN%lga}3!fkJki5c?mh3x0F zu|dX}$DMpO8&GG3Kp|R+9}z0gqHwO77Ecol7AW}hwPru3nr%OE!c<-T-;Wn^8M!BH z0o;o;M`0EilR_-1DH8Xpi<~@ls-5U$;aRpYhJ%ZwRY>Yzexhy8QPLmnk{n=2rMk+ki1{|m0fz(6n1P^O zX9CR1?(5WPRFH+9NA+_vxJ<}F2#T^2rZ^?J#a*x_45Gp^oNjPUxzfv?6h4I?MEfRj z#N0r$?TD?jma;FDO_;3puXa5fdl+|$0w2#k$5mC0Q0O$I+AM@j9B)U4OY*P?Yq2S^ z1Bo`EEFnxyR`jjIjt9R@JQK}(f5GTDNh}bt7CHpuAfZ4E>U70)Gfds-Jw&OUX*IUj zD5(oQ9~0J@Lk*dgr~scBp`q`kD$XhtRd+Cx(pN~DXUudrE|HfJ02#DaSl>|MW?US# z*%Z^yz4-g#!~IY)kOR8$aen76U4|3Ni`k%KN`@>hO_doT0?_k_<+vIR2GbJB6tawh>bA>vn-%}eJrA>WFFYpM8Q=^5?%lM}DnL}B zDXj;G(SPMRqbBG*XAaJG7xARgg{%?QYKVK-{kyey??$l^tVmRhv=o!QS?}9iXbF zw2K{vp^EK!Ly%YDO}#ye0RO;gjc zzzLP4*XgRG`LfZT@e0!##Cw)!w1=YI`G79ho{&pfEmthL6SqdQGb=QBy;}Om`La$D zK9h!F$9UE~P?v>or><^#;MelR5MC|*{gS!N6W-o)7)_v2Bn_j9&Cu^BoYe6SZ%!^p zLc&$h@7ES{No+#Y%fYB^pk8m5Qf+eWOeC0Bu3PuhZe0Vs6LU00JrhGj2>JvkDcXk? z;kR<7iH*caVg+P6q4x=5+*%R(h!$N@f}~2N&{0Z)PcjiaO3$oUud$qSnN%P!Dv3Su z7!K&mZNG3C6ag7s!eLwsIDv%K6|K~Z&SMdosk%YGXgAdlMd&yG#8siA@mCY6r3q$) zlc25OAg2^wI(uSgc*i$HX-}UXq+xU5;K8$q(%AHXUcZ}b<}~_YD%K-nq`?nQNl;Ql z&LhWljQEo6@4#WAoo?f!{MS<*PO=lEn=c_@5Z@+kW$0syG@TYF6Z@j<#ZYm0>N_^R zUAtn16Mw{Z^nhr_*Al@Uq5+GHYUj?5z1UR(p}?-djBfO3j+p^rVn2o7qvTJatlIQA zSM{MH(R1D#2NI+A?8?VdoN3xL0n#~;!-&U?Pm>8UQYDpFy&R;E;- z0-(91v}%MkgCVRqJ!+-fCH6#RmOfr`36d4DWHf)#VEiV2xB+bmv_Om8>9uC=kMT6q znn%i<5H!rKRf8U4mS39!(a*{H(w~@b0+hpmxAprKg+l}mJlh%-+_?=C*W+$TDg)`` z0A6JHgbPQO03bpmM}v6UHmxG;o7uF+iXZJz>q7m!+n6P|uQ5nJ3;9*qY)WSpNg@@y4ob;>U9C@d%S5^oixd51pYxh}dWL=HprH6e_|Z69Q+I zxS%mRmMxL6WyDGTfvG|kcPKjpUaiE!6nSzL>kUN^_5AtR>Q9q_9a?wSZXmT6U;?qx zz2ZsGNX4|%{+Da#xQ}Nba-GtBKwAgTiD&d@@Bl_42v(s;NVb+y12zk1v#Hn=kBH#7 z$$dyk4tH>14o7q&tAS{8NaP(ic%3LKlgT-a8nsa{4K1Y&WIQ;~22>i=CLhLzYrU=) zx2enj*@1B-m|Qh^`h>pH*K^Nr#!ae{dRsfXy`hHHf`p-n=_F(px*cra z$6(YXU>1-Spkp+F3i%HcW`BciJFr^~jX z;L}%4VcE1n0~z2O5m1w)Leex5sebUlNtWn8XQ=IGvvt?wI1WU-od^H{iy3*r%byzHmeBA8WuZP`k+#F1aT$Ka5dGlsN zSRyz(P(TZ7oyxv+aVty*HtjOePFdIvUJHRZ?sgNy3!I%d0l@_PDD(dmXi=jkEI#Db z^I=Pk0v*u4LeEs4?OFavpcZYzhAJ$-rD@dnyHd37%aX=T6Nri=Z86UZ*hKBS33p8_ zeLL4rXZ;>pKRG+INUxzlZ#L|Rd~9y+kFDA#zA-}x^ z+=bJa#mopcnq-))dD($QwFT+gx6ej)m%IBO26^IkZUqlWGel_n?$Pj~)Uw$6ije61 z{hOTYy=ARPFobQge`3`qU?ZS0xIkLohg(=HUPbi?(GjP$C`==K zT}Z*C?1#iM%JjiFZ^_;94fm29xVB$0_+9yI0UGLnh z*H%;YXi!A}AaSwJpLYT~GY;(q21TGrED0Y~T`lATOv&<+<6*;9Pt%G!%csI<$P5`W z!NRbg6||B?bQ{R#zYl&veozgxMHirILemN~8Gt)t-md+d*b_Qmf08~U?wXdMM zcZ_)qYBY*tEzY>Rq}Y0* z(I|6&@vekp%rVz*owNAF*p~7Qr!hrX=so)Ctsf1%i|*VzObDZrBM7t3B0j+ivx!f? z)G0G#<3td9D9RpD@PBHs!B%P2LQhXLx&vT30w}qsT*_rr*3w!J_A*>4=gJCc<|5K~ zv}WMP-XYnQiP-O%4?Y?#gJ1dA@EwCJc(Ghgf5)S%kqocOAqJCsOEExlz!5;G|!S8~z-WDMOWbegYD!obn zV0LSY+q#BwNk4(9m?=wH_23%XvOt+`c;{bw9n3bWF%d8#5Fu(X#-W| zUiU7 zy4gmrOJ`mW9aJ=Z9mGK$KW4rYeok&$W9kZmRIAqXcB`2|Nkk0RI%=PQE<`b1>9Pr@ zEAR+Tmu?$&2D^z}7_lszSjtZI>@M9wrkl8ec4HZoBd|v>v&7FZK|Sxyn_H&Z00JGw z>*MNit+q{MJsBqR8yJW*FN&bem)l)uaeI9Jz<~p6*MEDYNy3w&B2)8taBAvGWu7!` z;Pf?@*uR~7UhE^P^}mwMNDm;%ZGNWhL2>g+f>mC!C<;QWM4bBSGL={ALF$&$4v3tU zHvl0g`$Fx6iP)^!&a?s_c3VX*Jqc?>pJv? z3op~_>GxW>V#NbQ9x*rM4Z_kQyGE&=-QHFJ(^BZ75g*)|)>T_c2bm_* zI%FzfGniuaR$2D9x3s+0N@s&9&GG?~7c4j@v)8*IicSy+`wNu9uyu%j!YaWfLjg_V zfL^&c(P&3CPZ_iJ`YXADK*A25qu{ALQ4qr4&9Aycub*+Wha3|}hh{yan3dpjU;EJx zU{WB~Koool(A->oW43G=XtCaqJ=Z{Di5$nwu=}mq@{`TzHU2m3zH{ed@=H@7KR?^Y zH*Q1|U{>F>u$b`B4I^qn2EY7)B8g0#mf{075lj?Av8bPI_p`kLSn^*Rzu6$IyB>%k z;fXsaHTx4tbFM_Mm(~^Oz}LQ#^Tfg+Ek6L(K2HVxgcOFT?7M+Iz@0FNAsV5BYUkWz z(YM*@wQMmfD%l^gJMQBCVOi@Kr3E-e^Z}MMl(V^#&a-UpFsoKg8;uw+K$tT<9 zusNxG?tNkLgoK=S-x*TIBcY+}-| zfD%rr$EX9sagrX2Igtd7!}`k;?{u8(+Q zWWcW<_iNz!9D4egd(?voO;yQA3E8<`z4rv#59xzAK&v{%AjuEOvLe3f)?*|+UDIo- zGcfc=_kqSNHC@6n2R&M6J9D1tDgoL+H!Lm~UlbSH!Tfw17m zXO7IOCuqi{?{|Hhw-67gUJDPnOx}QOmcUX})xTUTXzjfO%G9&|koj!$6a)Y11ap?VgB6OQY6VdJsoQG@^sV_gu1P439+hLKM*t z*I^s{F0x$|E~%ZD|6LLZ&ZAbb-4U&6dNgck$CdtD%1$6$F*>Y9NcGRzjzWL9^`GT7UneIUhnGHtDzJ8KJ<<5%7>oi@0Z?kJ zYuVF1tX0dF#TD5<-9&k-wdx+F(Ac^2Dt!k5#TnS8uejKig9~&B8e~l3jIa#Gs2W$c z4EqF=L6S9x`qb1Fca}b|`D%fXD3$(N>S=?!qmM!XZ6+Fga(F$O6CpXxpZ_g>>j3Pp z1OXTs`OQ(fzvuP18HGQ=u%TBZb=aLn8tOQnQSJvS8kdNZC1tanJHfm2>!mX zu!FMtSG9a2#vT#v+H}Jh6GoErJd8vZU)Ux8!>{U|+hN*_q)i1EFE`bMC^B|FBNBgo z`!;fE((|RJwFYUaUXvE@5pdrHr=Whfm_OeeKGVOS zbdCXhl5IxV%)yB z_C<1-#BNL;WoKvS#rD$lX#1Z}va)g~Vd0aunYhxwX~nk*IOe!^$AcYp;OME|`A{Oy zr7N)C)pxd%;smIgPK13>ircT%O?y3gfz!O+j6tFdTT5N_!jQRQ*8t_%qmKrvDT-43 z+ER`Xu`!^O#c;l4s43+p%=59&v4L2*8VOv6#<>trv zj8s)^78jyG0x>4{Z33QpI@>5s^e=EG?W&g~r!R+{2KjIbBwLs}g}1k@rC{a_63wl+ z*Bnm}eTC>lN|9LrC=pcxev9b7Ty{Zt7z{Z@Aqy&s!9=to#KQAB@%c_;q*CtR?s^H} zYZz0SS>d!x=qZDljd6C4gZd!YdDB(PC;y0N%SY8~)ArZa4a8nZr31*LGk^~qg@}K& zq)bJq@oV86`eQMejeLkKpF#`to|gN{?jt5LjVVRdYpc1oswz~Z1d&#t0c)&uTb1n% z@y$%y!2T&}G`~fS@L9-xNRUf=pKykg^R`ZE+@{TN(@pVb&u+Opm6uV)Qp@oqND}-> zYCO@=N)e<){r*k|A%Cfq8B}Yn458<|gX8YU%;W$&iznI9xz(Xax zK#xRJ`iL|k)YQsrNvJpr9_6nsd1t0y(NEt$bc%=l%LOR>YuS-bjeh(Ln|pd=f5Y%v zeiPE0>Z?tdS}R(8it?1*46ifS*Z3c8nKY^bess_=YiX_R%xF54IVm2%VdeD)BX0$ z+x@lQ8i}BBgFS=)I`sV3d9KplgXt<_@*`TVbs>XNb+i#3T_Gr zzNU3=M94!M-zjyu805rWjbrij`M3o#Rhv*5v(|I=Q&YTwlW~Sr6bOkMV;wa~&U}Dp zq(FTvk)0DLhBEP&7BhR*!-XCykM)tak3x=Xrkm%LrEG)gqCUm z$i>rhVxbkX019h;O+~Ab(cXafQwp3kpxFI>86ehV5AR(zU zj{7tN@W-;U*clA8QyYas-9V93L6(xhM-%=sf1y*49*>WFV?3e*A#CD)HEv3~lZHY! z2M`F?{t)jZSSTxcyjFxlF}bLSI!M0=@Hi?{%o8%SCu;jrT3Y&Uv82|NXb-wDO+7*p zUiI$d$1$Q5qTBy4kCmE3(Cg@UR+iUwZh|-Aq2-9SoP@*F+|b5!c5&G`cutr+o!Yez z4pDuMB91swYUHv9&~+beXBRPec4>xt*in4g$R(^`+nQU{6kYvEO@aEotA2c!f)gN8 zX7Hlhw{IV!#LD$3W}JNSQTC&dwt%%D@T3Q{D z>_aq5K$&pz^E)wUo$kl68uw7~Kyoi)C0o~8sqotZuMWRYEbb1;yk)m35tC+Tkb4F| znCQgjWvSBuE1$EM6RC)FhQ>)1YS|xM0HE~3ew>8AauACqE4Abyl~kUHL@CrL;rnQ$ z)`dfIpPL*$4f|QM`RJO8kdX{}AueXcoe0$N$mf|>}{W= zHe9}yRDp@{gwG`HC8V;kZXGmkabs>l0QpH>u*2K8x0EJWkpVNCzFJ*} zciW$RTi3$RnhoE$ZS~D{m_<1naF!h|RVZ$CkLz@-CspbLMJhX?xM&0546qo;^8~0_ z9vNBnE}QIMs1}WRa6XYvgVYoWa=P>KXsa4Y&BSTq#OLmsS9sjcBNd7y13A4rnW7{T zMv}MusH{XzY1+y0hW5fkAoeyktlpfyPms9*(+#yBu2ztfOFZB(=B%j%a4k zSdlhOas#GSid&8Rtudx(i;@5WOQYZi<0U_wEPljp@bmxNpX3zr!_MYM)|wwos{G@B z_n-dXz48C0l~gwvC@Z8$?HJDPQ~2$AyC+Phm)7eF@A`e};^0v>n_cjHLG$iMz3DI`O>9JFJ`;@`WD`u^?1!!&l3e6&rVHi zX&I7qC<`>gBH1de!~2Ze){>a&^jth|493=4HGZ!s6SL zYclOO8Ogj}=oGpOec+8sX`WC?1j<>o>ye*pH8S#oog@8_c-nq*t;nB+J_{O)@n87i zJj=L`SewrEfoyi7t*-|^o`V(P?JW@#TSdULW5M>w`a0=ndB#$yku-pd^(onU<=x%Mw>Ed& z-hJ9iX#yp~mf!+T;J0W$2sI)uAY27Y%a?HlB#VH2BT#x-Crx|8l!W635WyGCtvDBj z8zt(0B4lQ^+!eiy3#$wUM2a|+bSDVjh1(K7D7X}y0Dqb+VKqa#r3ThSSNGHBjF<9y zA`86{JlUkw+XMgc&6LKhlLWSvyXT5mzvx28C zZx_ZVKCP2}+UXs~asK9dK}2-|R^U*@yYK`K`spZhUFhHz4J-)vIcF;@=Dr>x!LW42 zR8>}#Ys-}N)_Ne^xN)%lyv+!<22lH;v84iPp;IhBv=AWb6 zJ@q~db646(o?lo1*7yF1TA10x>?lKcA`ftG{rd#{*nI!~NGT`?z74R#=<8zyyyxBH z^!2S}g{cMin0iB}aCVudrq}z&hqm_#JpAd>&rm_cSaP=)m06FDdm=2bO}IiZ}Tk?vV=~2 ztMo|ot^JN2+49V@Xn8ZYk?cG)7hoE^YWkw*{14-$haf$omZftuOapjM2H~#s4H1gm z?~>fLJbl1MJu@n{0%1{a-4j-I9xyg*zf&I?oTSH-^syv1IeN{SzZ*IB+b7gsq6ipB ziE6nho_|?O?{P}$%OgaxQnKrJFfF{uambLe!7DE>D*OIjWM`#e z3N!e2(=?st%@4Bug`vae={-*U4*f<*nlh+-UEx|UPQp$K%1v~1MCrEv`|~GR5$VdX z{5vP5XY&!*0<-CN?t?%>zqRyw(LMA>kN|ctZ@wh?_S_ZNkH~x?=i>=H;?d*AnR~rx z*s|qe5!hj`ls-SV)T#qE69n)PwNXZuy)U-$68Z;Ocht67GiM5czM|wDZ4}+l%%Q@9 zO3jKFj|W;?hyR*OFGsh-y6bWTQ0I~p3D__*dB*jaZl2O#v+mhX7;VIJ_Ydk>JM_(+ zX5+<>XDWDKpZknk+q~E87zBs1wVx04`{(Kk%Bq{jEyxIr|GemDWobd|jNL6ZFPTTO zB&36PsTH4I*&1{-FtA}N?ZbHcO*QjMo1uU1j${_`RMGcjW$oGzMXZ~~Et~T`>za47 zWy1K+y)3cc6c?*r?o>zaGNv+iN(JZcn`k3N%q6G6+0(I+a698~u8 zoBmuho`enr!r5wl_L=d&1s7e`5&@1qA)U*djT~b3I>imjC)d;X_VNDXL(U~K5rld` zg1XQ7>DZOQnAZ`l4sA1!uf2oFP+!?=Ww}vV-fkufgxHSjsC#390ZACvV@D6~$Huj*da2Dp zjEd4o^Yz&>K}XmC{1%lhsp{4ra_+8t<@dLHN}rkRx9WiZLo~Nx{Rvt(lKfxEODbkB zsM<3xPU|W1fyUZ8%Fo-DE?ZWTIq%-*h;w=fcfI>!vJ9g$j+)Z)N;8UAqWX{=;Jt(` z^N!C=EEs3?8%LW&FCgC+%BV3qDCt!#pfZ&s#WiVLstug2$L-ejOP};Sv`6}$;P)K| zG`bb{GqPSAQQq6C+tX#RjebM}kN{z}ymQM9ryVHy_ZL?qYBegRtJnEPrAW*mCUUF2 z@2DkwpD!6;&hCJ<#lL!0MR8v!}Hq+e!$Svlia1m6dG-`a)qGb(9jO0$(_A?UuG8e-o`F1W*3H8 zl^0UXYtpji`=a?S=jRTrC@oxY({k*%an27kZHoufyeC$7g%M~YVk>|XHlK4c>i47Qij+(q>ALmj zUwfq1mD4YZ1z;8C6)v*9E?9;ttE z{>Sa9RpqlfT^V+N+GCCH6%_^hqICD`JGeO@IQe07AdMB}kFTCTb^>*X8Z~QfcXOOP zIVW6u{XciHIB{Tz7Dq2%U)J!Iy1Kd$krIEOm6_x(n)=JV)7g||ZrS#bF%}-2^AN1K z=fW>jYpeftK6|9*?zf*V6h1lOab;)nUqqf%V-ABa5;j8iZBblV{PnA|m)Aidflj%q z6gPB8Z&%`h1Nl^q!IyemT)Td~&Xoa+vqwJvgxgGM(z z#`N-`Y*X0oUR2a^tH&LVzJ)Fp_}(}WoPcyw5K%(V$IqYlne43oBlCQNrcJ*so7c|5 z;_1u+cW{moJ1soCWtO_kLP-3yfW8wfXkf|vF}xdS^GcUvHwpD9@S_#A8lSYYJY0B~ zY^sFByZ+w>T%~$|XmkOEXVPEjoI553Bx);_BZGpH2zYzoCJ7h+ocXmc4P4R(S^i4z z=a2zcYh}dHjhcA$9vu=?Q?X|k79RanP|&Kl603%E!ZvB7H>Qs!P;snZYx}SFqetSyU%$+mjywC(V2jEm7@Wl% z-R|S|v~o^xcmU~B{D0!(j{uJji}k+1CA7#pdfbp`&YKvh9D+|)s);m#NPiuSBhq{S zp|59!CdJ~D-h%KllCL7|*DbsWlF-Gh(9)sT3TIJ(|%G3i%}b#YidN94El z0|FD>aYA+f9f=>Tt^+Gz?J3uf<iwL<8CD}9Tr16k>*XQBerQXr~E~HtH23vZa!Y$Dbysc-WUst&)~RWf^WjI zxxTX%keGmHQUfP9h_y7A^F{R2B6t{V&*M>gp-+o<#8MMnj5wUkW*OY$Tk54OKHwop zlUS%nbuV#Au1S8EN9xzZccMo*>s_mTg#|Q1A>q0osi=|EN4~^d9wS6YI`jDWo7vg! z_*An%m-6r5JK|v|j@Q$&H%j>Vmjql?8k`GGy!cp-vnk=kz9$yd{p@GEktkY-$;-6r zi%k9|qv74NBAWvjF>%5x>Ej6;*?_ory|Au<_d9Ewq#6|KtEs6Gx%bTS`|)~{W3kLh zB%=TP^pr6?<0HpY4-+VDpGdS8o!emx{-{S~P4w~Ij;DOv4p!Ok4-@jdVoq+y&Yf=u z#DL8A>|xH>p7pSRPtUD%Jf!OPc8YGu!Th~j1bk|7w8K!)kGoH!qv zRKnXNp3)=vdI8pS7y0z)(c_(z=3y5M-_vT)g=}UAXN}Z3-*fYi+n0W<0)l;g()AIQ z#f@f77b+(}GK8S#_qB z73C5U{*$A=X)cuYduLJLd6|_Cn`rc=y`o8+z7J2?82k2Km{P9PhdMN63D;YH7N7?6k>mr&r zY7|Fg75n@fa=h-;@7%`dQTvyjqxIv@>EAM+@}=SPV_PcCckkbk-*ETl&9D739?4r; zK7C8OM>*j_%BS)as_+zVTDiT<&d$y~-;CHc{^ut^b6Ymko55THjcX9OWJ>nfDVs?Yul>IiYLzXx3~we0nQH zP+Lpne({tgd6W++^WfW0rksrFV=kR%#C++U3;yBspWC%M$x2;Aqs^z4bku8Kxs*XP zip1GH&s43skC9aS{m8iEE!|!|I7OU9dLEOT4Shifn-@=+5dM36e{!A?l2|aycEEt1 z-C;{HP_d?|3DgQpft}3`VQ>`{Igzn9c4-uTM}}TXV7ojfSh`&J--u#{C2{pLqnbwO>O@CvbiA{QUQZK!997PD0%}l?< zWBOm`=ofhO^}@pR^B!+*o^F>{@b>MDpfeM8+@0>-xBoRvmA2#8Migl7E4ocT=1gO4 zaddw49ohm+OR`LTr`9~yX49@+ADd)1{<)a~fK1eS)j-oW(~U;*+-Zxag>Glg)|Kpr zgY4{z7a4yE4_93AjVEP9WHi4~iN~8oV+OBXU=~*ieX`unm7;9RPmwL!w8<*Ggrb?* zkD5Yd(e3}`WIMI2JK@dOwk{l0*b0b-+DvKeJWtb4x6gQbUH=h7&yMzuv#?Zxjm;Xp zr`htmT?@$2SL$|ws2zIm(X=-SV_jT6{Ox+eCo5w~(#aMnwVu!JwWqhaSk{RXy}h0l z6%~a>^)q`Ld9LpJSBDn|z78@E&IaZAlB{;zCz0X@^hb?QcO#u|?(`^Rl)g@)EOEK$ zMt;A&iY4po58K$dgtvy3X;LU7E;#E#wPwJGTVo)uZJtY%r-=5e%9-Rn1`=c5sR z@rjMB^@~r|nF&$Iam%Jy=uvSQ4(GH_H@Y9(GOnWF#%G`6%p}4?$G?~J$HH#D2}?e7 z_Ki1;ec$p$cK2Rizun6C)M`+{GV=%xXSXw+<8*gFcFdhw~%xgyzcUZ}|uspNC2IS&j3LL{Oxc-cRaJT2sDxNyN zuy>Cs2jc=S2i_{VzB{)2w}FFhubRKwbJ~YlYArQw_e=@cTXVkyx@7MRV3w-eW`A{2;=0z2Q7;7x=ot2B^ zp-taEqh53ywCt2;R z4s9dK_G@6EGesZNw}sn$F466$(N)5yu*!_E{>FJvj=58QXt2fJ&SvzgOFcjZhZ9H? zeOViFdV0d`88l4)xwg%)mqWX#bN{~X zNmNcLk8U^LK1bX>UHm%2xilE)aW8P`_LeoiZWyfl`Td4uLfW1n30H16YtqDjeeVaP z0NPf0v%S6N9`tZ_b)ECR)?3k)CXMJ+x2PLAQjdQ71kpIlJ50c$pq9I_p@M3e z>`K1ru#g<@JsP`3?++c&UHH1efMx1gBVAl(dz}YJ!Xm{y{{#wYVytPat$Esf4+}1n z3W{!>YSDN8?<5Z%-fc8(-=0TbvWIvS30Ev0FV0{(WqkbAqQbg*mM-=C7wa_9Dq9cV zIE&`W$Zb|+U@wM`5p^8o_O9HXbabrLj!j;q(l6!g+l`?|V~@GyZ@K;odi?Ok>Gx@N zr}cKg?QbO|vEJ^Wvm)v3GFlnY+<4HQs!S1CM2I=#$Sp%-;~|p!9!iX)+UxiIopP;lyAAyX$c#4sgBv#q7fT`I4>UC z5k?kt$kEMko^RAH|I9l`;{%AgxbUq?aufJVJuOd{o$Xo2 zcsL?TFAO7>hy5ST))znv)%=Uoiv#G}-R2%Tf#h@9#6mbNJ$g*LRw^<`GLm9uP;y5d zbh()$5g#%DvIw_o(QLhDmb-F!!9<336`PJLEiQrXUoOcIA*}ObHqx z{9@@f0zD*Ke_lMvkfJ-qMu)B!ijeo(=itZqf$1i@lRex=(cJ+g8^shRKD+a2LgBzUa5+g_t!frA&i5y*O zK3H6053R-S#LEDEjUoOL8xCNIQ?IO}|BS_@%2ExuJ^tv}E0@dxV(PZ(1F)Au3G`R- zj+kdOWpU?>OWXz-L`%0+AQ|`2?+2(C%n6=E2rDqEpz?SbaFaWC=Ur*#I~zKT?t_^0 z1-{AU^X|3;RL;$Ajy1Th`uz1`0GlInMB!VBbkm2!hBV z_uCnN{~a5;Nn3qi#tVq~f_xC7CmuC3Fu0sIPv^YoS!=&5?A`A7pg8==Vwl4T8K=ow z(3g8U^KImwJ$tz0Ls5#|`lNNj3brm*G%|AV`#$x)7>Dh?cXu5^t_T$5YxJC~lb%u2 z|Js@VxJU}5RKZ}aXZ--TUnxCMeJ>u9Q6f^xdGyCU1VzZTT3Ur(bZoN;MqNV9P3Qk^ z<{lyqs8S19XwyzVEw_M?2&z)8ud@G08c|*>n4s2r&PAx6pm&HsP@pj$sTffz+2@@O zHHF+r-70H-1>CFOMLTC?EbTor6YH;JA@aJ_?{BRi5l`p)xzwi`l|uPT3|zP&UV3m) zQfd5~B9RWKFG-PK;1$Xmp36!FgM{9`bJ^{1EI8h=a@(*cyI@)eukWR!>=tfW@d2nd zaOKkQ>pa0Hl13Dlgo1zf=%KK<2G8p(gz0l-Mt2(!xdxNEXMQ`HfY<62`6er6loI5OJHn9YqwG0$vk5ho$RyBex^2h9F>BcWK zZG%>}YUVu7vZK0-e`a!dt+#6;*C+ORt zH}fX+!X1?^CJIPNdEaPSQ>nOzRrS-#EzJzF=r&#>1y!4w6tF_JIqF9wz5{3kN-RdS z#i_YpUm=5rRlN;692e)A7Ir~aouzH}RlUq!%8```lu3tQ`dL|+HQ(?}LV{5W+LE{` zO|7`hx4Cw}q*ayKKV2E5QFqHf2V!Dg-X=yB4IBbyJWkPh`-!=slu|LcJ>Qx4fScuL zRXLi3dE}r$krHajPNFEe=w4OPeKjpN}vijcD~8^RSPE5gs6u4YI=Nvo%4 z`C;QB-+s$E0|>LpC`YRL($WE_O*g!c^El#q!5w{kvLRGuO|RHFMhm9^=l?N9%l^}A zuZ4||XL^uosFS|QClnxvnu-&6-7n$+*b5whmFi17(kvwNABC{s=Jv^H4Gq+m;6I(A zpiwinvM>+Ho!KL&GfY1rG_XLNfVm@6r_G;1x2$M+3gMTaRJa*PSxFrPPo=fE0(V$~ zZg>G;+E|bo>1lxoaqgLAy9#HT>iHxJ!HYhGgq`V{5|s@u@Uii-`c@49=1HsQJmc~Y zKy9g^rR8jD#GxMta zqi_F2erVT2{gbFIa#_5Wg>~NK%ygE_1HQefTZ-O7tBK#>g6j5v=;`Qq?{2}PH9xiI zmtG)J>SSc}XKo(FiGbHPHrQl+%gM>v@o`zJjPzD19qH8Ov6vow(X4Uf;$|=2j_^H< zx=E;Czh36%6<0NCnSH!Xj7%}x%K1w_xlxUNz$vD zTQGXjqP{gyF1YGTs5F12Dz^`*59O3w`u`W7?th~7{m=Bb)JDol#&iZiZ13HrseRyP z4f*%7oqbltPrOxqOC!4Ysu*2q=AU5;^AketT>g|c`0obQ{}QEPP<`KNrH>~Xw%PXB zeuBI({NB6G0ht?j?08``vumE}(=0uGeSCa&n>8^Uk z@fjC(t6i!Sf!WR;dTSs2V_sB{=W;LHJX>ez!(O*kw6=>c?|vw)w7#)G#bV5#H*{+~<$@qnlA_QYeCU9nCPy zUZ<5_5Zd|Bwo~fzyWxX~>!Q+}EDDkZf4tCFrdZl#VJ>y4Z*zsosU&*k2Ht6TScBtoE~q`fJ? z;o^Dr92*$-qwEI z&{NI{s!#m(VWV!!?!2j;blmDMpA@*mX{P*I;ghF#d`8lqY5tQB{4~s8e5FY$ zyg18z*`zkE_o?0L)^;|W)5v+0{3UJjp(hLCRy1uf;pvp(amRn=xK8;JEPrUOtyP@W zZ`r^><0g0eT9EPf%=lx4mJ??u!fEGSdC!l}IFV;%elO=CD)NA+bMvR7-s^X85SJsXHDR zbT&6HJ<~btPTrEDt$r4^58oH4`NziVyoU&_2wzvQ`OLUcTjSfv2CVnEetj?fi|t!S z+HddN(Pq?-lAnf|U+yW_)|Ic+JvMOEuK4GZsusSwq<8P`-8rpR*RA-e7CW_X(9GH8m_9+^E_${ zQ~hRkoyj>d@$;FnV&sUyb!)d2erR3$A$Bak20LCOLMdnV`-q=?A?+#z1qyopA!|W^ zOUaVbpZ9iIZg<-D_k|vvwobk6?Q^51cCYr~YS$+}{jH-_LkkZLP1Cl|UT@nu+aPRe z>9e=}Dqi%zxphXV{Rs6Xh9}lXwN%zTf3w%8Q+b^x{4wozr>*VR^!Qk+6N`HaKHWwXTISnvEgG}!fFp<(5?!Gj08-)Wql zkdUzQYmK6&_H_(nEwXuuqG-j^jlG5hk9b%JGw$2qX$AmK6AkmPZ#Q@$^){lZBP zU-2~`ot%_A(Bv_!ToXU3w`yycwh!%`-`Zx6#$vdN!`@Z)7IGFb~bNOPDq_ey0vY!U|!=|dXU4#6e zLz3Ux4$Hmf(4tbe`qSDz-}cvnb9Lt0w2OHAHqNqhg6bhy$Jen>PKk?qb#9xh@?N3Q zbCa6`kICojG#S*sOZmmD!B(erc8C3yV{~$dvHad{N4t#^Eem=tPq=5iY-~#D{e`#m zRlnae#s1#T!uid{DNA13UTr^BMHhFPwZhVKQ>^38?#~}T-rO!fJYMsQJkRihy^IcB zztQ!Z|zVt>~I0R{U48he%Ulg z`7^S+>hrr@o10p&_(s$qS@fp%!BM}h3|fCd8xIF>8`?Xz0KAP?2!NbF}|byAo#$;MqM)0ij_B6 zyA%z*Woqx8@ay&dL%e(0-)dh+{ubT$ypetH*Yd9l{|-^K$H~9AC}XR6-=CupW#>mH z5&3HV8E$b+sk)G>hgxrnx0@?}3s2hQ)mC+<(T=oy@=YRK~ zMyjF$={A%f8aDY6IRbwE@BJxa)pBku+5x${U%@>hQnWi(3(ipb;D3fQnW*UeQxw`5 zUrzssd{y*R#5TOWyktBc^axnUAP-qDcy*`;e+@^MRVGb&u&tKBSt*=IYw!o9E}?6wz2f zNc>P19o!7cKssL5!t`&@5HzUF55YBv^svkPTw|Gy^vMV)h!7C!RcZDbs*g-U^wRTnko9;^!r%Z&Nbgjp^OY)I@(qrOruLLur3oxUWjk|13#NxocX1FH(!Mx|UH z4-@7`D)jF-*hvgC0hX47k>#ka@BX|p^&t&_#aA0S9;B7bnwQA=&FPL*_B+U5M$xP2 zz7-r;AKSSZg(4( z1h!%S;`;++*{Al}QA<;G*LJDsEHp}QyfExc5yMgcplG1{^_OFS(=^UCyxO=k8M@GF zl9T(St9pwS8&*8HoG&AQA(pJ`7_WNt`d?5jKtx67Y7ZC|vAPTyl|JQ~)yGGh?Z4@E zUfbvvBT+Q$usg_>4Hu!NTGRC7=mP3YU;pCc6OH=)_M!zvi?JL!rQVUhZ+VTe@EPx5 zl!b!2OjR&ptcbqq3n#w;;<-V$tX+)MHH2fy$y8Q9&O5*9M(KnCHc>V?3W8DV*ROYi zjM<|8wPUz&fMu9+tV8BsD%%o1b1TIIWW$z5>yL8{+#+xb4DVmp5@YGmY>jk-ihjew zg}pth-;?h|ky6xZ%}>XNg;fh2^LDOo}~HL)w}!|b>L<^tpbhgHv3z&mTK|Yxp_l% zhgYwo$#975J4bY|u{*?p8yohyS(pLLhvur)%K69CwMRKCCc`Kvd+Mt;tDk>R)#TYj z?Cl@O6mG1(i?GUVQNS}mNe$wN!>$Z^pS7C})k(>2?Q2D)`usnxz)iXc5UX6o-@3pJZQjgB!d; z3R&i*$uwD!DB`QI)O?^XC^t>i37|je)f;U$!ah94rO{?U;pN}XT{=odjFl7D_4)AL zz1AE|%?44x*)q&SWE~w^)Re2y*Jb`N)4U!+4c^a#{`d2WjMazGIJr;I8dp~qOfK!} zGH@6AEp#*uMJQZ`5C)>_`q`^?wIOgFKD@4ZRhiBeQ?bPPt+LA^S^Fi`M&O7DV>#2G zM9G|vs9zU%63uYP6f5Cd=8WzQ%=jo?ot*ifB z!=c%=YvV!s|8ub9ejD3f-64%HXV0RH!qb!AJ?I1q#RJq_vTAEg%t7D91(TBBY@fx+ zz=MW+U45r-QjlO-+)6qd%-i&|FwC3|(+zNFJf=0A#7S@l!hzXTCRWCv{~51l$~ z+D!h28~pXe+hzekP3!*oWb`38HYI0|FCLCsWvh&)s_WQ*u0V{*?X6uNEvs*Nkfx1a z>-~?V_HZMBSsl%U;gE24Gj~r6P4&fZh^H?H8?0}7R7NZ@)hnMicf;yyX*&?dXfSzD z%-!jWKd*9syzSDDX;?sYHPzG2L^Ue*2|%b6G&%Ya=m{wm)=6jpbfgnh-}Dvfu^hC! zv1U=#tFF`5SaBSErhxYCbufG4J$2+_eUK&iKq**|9 z{sENsU)yBWwE!o(z7%V_GSyq8Sy3#k-rRl$cc!0a)XQ+4=vw1k{FkdXWJ1EP=eH*j zi6C~AzK$6yBL|oAc=dzNIbGDx{AydI&}4EvMdKNZe^YIgJ#>7n)zR5u9%!^lMhHl` zbM;aUai>L2Jjh$<6e+Ks0bG3l`MTaXA0HDB)iEowOjy;{Z7K?#j4~!0Y*hVgeNOr3 zYY<^OyMJGqT6V4Lt=YXADdn5=L-C-nnj2~U^VgPfZii&7JLSykjS}sMEn2-%--pcz z$iJrRK-J0nEDvr0CPmeeG5cBf>YKS*|B5MdmhUfGmym=@Etb8{@vS~cCy%2U4eG3^ zwljk!ZrP8b*{!CEBeSJxwwmRp zu8ouWK}{9c#{u+E?J463>x=$hiCU3P(Wsxr0t19jcvV6kiewX;!8zkgqmH)c|Ja$>PM?7bcW%(r7>%% z((F?9ap|GD#JuRP3r80{LcK*o!Z5^4MLiy3HyY2jdpr=nkU2k4-xGhdRy{aBd(lP# za$Bm5L!7aa`cew?Ps@*&j!=)4`VRW<1fk3YvQRS<5T?ZI>?Y- zI+kj+a|p5AQ}tQzrxTS3vu}L|>|2lMfQ;{j3@RcyvnJQXrqY($xw*FJ9BZl`jFJj$ zcNp&x`swc=*`J36+GcBZWvIbINW{~+$Bsry^YpVj_OWV6B2q{qlX;%9$h@GoYM+|< z(#Y_^q~#z{1Vag~QDP)NHZY6CdQlb!RmZ{E2xng)B=Su&BS`r>0x6Q#+> z5WD6d7!q@d1Ksw047&QVH>g}mM=JF8od;X2CnBY&>@|6^HF5^k*Bujz$cyAuwc2Wn z7Hxg{yBhQzUIceSYMGR&#<;lL*;docf78rfB7-Y!HRpWyEWND1Pqohz9C^}k6_jnY z0d|U^lMnjgk9M{lgwTB-<-VFuA)rN=4X z?9_w3$Fc<|dplWGeO@;spu^*!u|&ee2kdH{nmQg5@?RD2Lcw@bgFU9o<+e-|4Q;>Y zUb8XR`y=PX9;>0QM%e8C(ZLLw2Jsj9DY_2P*5S&_?v|h*xFl5Q4WdmgkSRe%Htx&Q zWsGz|YD_r)F!hxk<|X^~8*U^@5k!y2Ti4U#S{bm$o0EtUc#76K9w%tXpzC!|$t(*I zIO7R%hB2F8Kcvsx$`Qt7eayb(PH#s$9eoDXYbxyeV+|dQR_{;IPVLIJIh*13D7)%o zcJ~ARHHjMX#Xfs_w)0SUFp*iI|6cl7x6eApl@?W0$}GdiO3f*6dNN|in_e^GVb3#u z+fl}s#2N35EP}Ifw!Sy>GvD`h59 zwn}6t3Mrx_Ss_YBl$p_>q7;>p5Xw$cq-2jo*)!w)obLO6|L^-A?{PfG^E~(SxUTCr z&hvYI$7eJkL#uxC6um?6<@XXq8>Yvi+GCQhF$yM#Af)9%;@%tIFa9REXJYflysW=5 zgMgi_CdN?%5^|m#q?2F;!m&Z?9@0W0UjfDr(L<$?45Fy_An0V6%0vH^%Fjd~Kp;oI zo9!P!;SZ4)m@cP*AfY`giKHC#fbhot6OD%deA3>*fxvXI_^@C-=laddYVwH9(&=w6 zG$7gtC0pdxCJgmO))J>M{XyE*07(CFyUSZ>;e)&Q&`8Sy(MW|Ffg4+T``h+V&K!4ANH9m&^lL^4^hFFqdQf3gfqQ^V-=W7(pPspC-OL(}mgI^nYgzIq)S&B(tC6x7<%eb^x1a?hn=x}6Ra z72Kjqj0#j-Fu#R59tZ(E5`S0pV^@eAJT0=s)(^K&PU2l=-~?v{)Nw z#`|v}K%$OP%S{clWW(CSF#A)2{G}W<1ZnR{BmHZ)BnRye9GkgpWKbo!>zR47M#3%s zpKtnJld~hM35y>`#TecJt@H%BF3^<_s)=bFLO8Aqxf+UtkJwu-U^~#$ksP5#Dz0mr z-QmjOGh1_~<1$Yist`YRLTmf2G`k0y6Pu@JCPi4IdA6!Tf?%!b#qL`S%!0tp>D$^0 zDQg0WMF%lccqYP|DY~v$1l;u`LZ5!L~KnnT!|-1{?f!lKs<2zpyu?G zI4qNElSP_72rLMIBPSX0Y)hr>^VBPDwCdXRvp9FvMpg98H!s|9u(5zt^H%&=K!r!0Vwv^13Zu_kZ0pu8RST(7{B$rUa6iHqpmzdTA9%#z zZ)?-)H?uLpu*3jgNW{gVI=JElWmacnfU}X_#~VmBRUW1Eb;U(T3q5Qns!X$t9~r(7Np^`z zukgQFakp)1qd&cad@$RTcvbpg{rbxXjAnBRrcsESrkv0+Bqi12Ft`cwX1Ce{lMSkx? z^FlrLEx4jt=`EvysdttD^@rb zCz2$h4j~v3q?@9IW-<}|B67{v)_zL3q?a4Ix#iM_mxxu|Jj8R*IoX;`;61qW7HIuRVcsZU4H3Yp2RKLUdIR9r@e0Jo_|ukVq?3=eL<|~msrt! zBEqdPa|8RYJ&Oh`66vQ7%`y`hJ_L7~DjNn6fL)z}O$ia?K-Vu>lMafS|7JuWiwMzl zsmK3>rh1ulUNtvtYu0Ew$8H^c+ROQheYk*#PDry&?v^v*mnKe=U23g!=%lmiTa5w{ zm8q{;y&}2YbPq(`58;A0u2)y(jKT&8|DKKwz&f_NO2*|Vt}4c5{EJ~4(OE3+BIGn^ z98md!)zs98*vzzt0(Rg|W7%~w&_2SsgDpn{W7LY2d4u;Az@t=gEHhn1Aair~<&hgt z-|^ZX2;y9Ny*puUUv6bal)%eF0q>HNF6i?crHNjMKGubiKJWcI+i6bOcRbY6R)v$Xy5-FKu7X=Ao`glP8tgD_u44A<}n#l98`|r}{l{r<;!Mz`!}cH%Xk!&mUplgR{H zxFALpkbZEN1O!EJEs&ShN75xo7Lne`k@)wk^Y4cZHec$`(!72B^(~p|%$%$fwWq?; zI#wP?pT3I~E3sRjb?k=7&l9^HJt|)wcdamWy{;cM`=B|iQ23y;a;f&pH<35(wYDl2 z@;^FQFt6=TkMV$J41^~nq(p;>JHg^v&kRSN_e9SJtT=5*u+|k<&8hBWg5DKT-+*0| z9#4^)UEr{N0d%7suV!!4Sc4VJCZLq z?Tn#HldDAf@bh^Q*{@&v?yNij=6$Rur`3i~}5xnEJh zHF7>9;`9-Okv@Z&daV%FCY!@s5ti5X|GCNUmAow|_ofPC$mGFf9z#o}9ZeBkv6m|c zpUnM-1$h1GwujEs$G3WGT{(L#&s7<{7<F}};#c>26A_0l} z21)?9M;NS-NF$zZ^tnv`=8K^J6?!R#reI?oS^DM*d%wG${{D&TT{m~Es-4)u6l0oY zT^pN*aMJzsjlo2Eu7rTKFl)5#$KApS{p;_fpV}lK)13CXVX!>BP)RT@PIrE6jh0H@ z+RBWG?O8|WeXjIoxVF(391@RlfszIk4A-hf=R?*+GwQlNYzN|G&NLJic_ZI(<2Fsf z`E_y6CgK_&5s@CDJ`mV1<(KGwF3~Lcvw)X~{eg<=+n<6gwc@`%4(c3yqC7V0kxeZ$ zkizXB`t$4iiK^JWn>K7={rvT9l(%d+If7pGW+_gh=I>5&)i@psOcFQ%CuFYNXZkZB{Zzu_`OPmg z`9&1IqvHcI-vO)`3?yY*JtBClieUOh(rnDK;N($mlf_&q;EWL$Rt&b53pnKTbpGNt z{=VD;tai0eqbd?4N8gq7+}{31O*V~t9AcCAU@ zUV0UZAwO4|Pthy;)m;}WcnD-aO*J?sKK?USG4XJ~+Caop$yG(m3)0sg;ZD~z`aEI} z_S9C^kE(-eS_vM86Y&?BpIZi6Mq4}CRwdN)7{1#Oc{I!TRkd*pmk8tZ`*mX@`46ky zkLTEkJpY5^e6C<^u58TK#f zEg+H9Gc()dV?rhs(5tlvPlcU}OMrymnUwKnjT`6R@I=TPy$UXOZ%ea$Re94ySbd&8 z_wkuqX(Q{6>g6SxOc=G9wssxg>%G#lHX*I6XL)4akY3Zdo{DF()Dz3xUbo(y{CSMQ zXH9NjN*pwalxddEFl+%$A%UkOX{r#zJtB9Ch0VEIVN%q;s#_nt1yYD0FDDBo1uuEx zMb!oO?15dYB#ca%FGdU6`=*~d;k^D;rRlk=YY$|EOXcnlXi7l>C_Ow?FLBzb{IKU6 z{bPmqO7j#Wq#n4rZ`$pv5Kg%9a{nRMaw&t+P^tf|l%XEwO;}w03O9gAs3^1p0d}hn+eJOlmK07kA zjkhWDmvyv}CbxFM+r4tx{ZZt_pqc|<7KN{bg2Gcs*Bs%M-g^BYD#jz2-=jf^w%>}b zwdntX?rsN*iS&|vrCGGM-J|CVpA;DEzLhz|yz6?#wSsHbuc{KhZ@cv8QtSKWLLclp zN*g9Oy>_y?K5HAg&ui5SLGoHmzGPS2tiE~-NU4Gt+EDvsn&q#pNKSpz4Ofna)BnnH0|&(FO^R9mN2iJ-M?h`cWgUv zWN@up_~_=zfy2%h9mAyl&E@v<7RuO}T^GpRuQ6J1_XT3Fx?Y-Qh_z?~b?3;Rh1*_! zFV|0WjD$r|$ zELS5i7{dNZwD&byPf4zAW?(UPf1qiVMD;5+ch~b=ycN zi~lfhYmRSA@+rk-_I5Eh*$bb37HADeo}f9QDq0}C#5~x;anvk~w`IU9WrPHkw=_}l?O6B)?F*7K1fskT&UV5;g z@4n2UmeoBMq*E7W+ushyLhRkZYo@61wA+DhyP6F z)c%%qLl=y=kx}V4oPaklLghb=>01@ne37-`P)vj%2BbIq^{I@Odt&#zIfl&{iC?y9 zOrKg+EN-nGEpVy9L?F^!?80yMrmWtI_^@PM3;pDZb4XlMBHx8>J=J1(LThW3rNlY9 zcY)_Fd2UA?iU0+2gB|oq7?{;iFw~)Qxq^Pfc2-8XdL2YPq3h(dgJZ9$g~&FzDnRl` z#qwL&8Z`d&&RQKkZdw>cuh5j)TP`jv7f`Y7pw-iXTrFe{>7~281Z{_J4V%Uu|2h<~ zu*22<05b~#R)F}xqRK|Z>PYHMHOUMQXC@UmjS6mRa9wdNBsi17MI)V2ahi1g!4eVH z&*dQt_v&jG6i4p#@r8!Us7eIt&9^%)Rm<%wy^5aSS`{{6r(9i!jr<0*rBd@1|;5>03dn z$w`7CXBtX}S7TwG$P@}+VfDW2ktzF+Ns~jIX%*I=NErlh<0!sSgdPL*WE<+Kik>b|KqTN4W2|}8*Her0ds0Qg?@Zg;h>9LT7S)$o$2=bw zeeHWF+kjIZGn>mpiS_mMFQK1}T$B`?7(aCSY5T0(dIVh0P|Ul4aU-gRE9iGVhRzJI zv|t4xRo!FtONR*d4^EC2z^Y|o``JH!YOl>AE5iAXxeNI4Y*{L#E|ovby?I~R61R-k zf8=mTdkz%Vf>H$W47BQqetAQQ$+C!w`zV%3TCT>1nd~|CO`8O%)j9v~n84533;-XJ zhG5~7yBloP`rGyUqIyC7CF|N4p@=X01OvCU9OsbqoEm>9vIXYBWvSYj&1sT;5PlMK z`@Gk$jRu`o;K(Lw=g4tTGRyxR$YSt$1`V@1(2XK*-5L)vFMY?4tHNPINUO=Zf#_wG zdX0vT*`@dIi!qHsWy?&x`~GK(ZC8J2$Q>pq^SU4adHzwfeSVafe-hP0D=QWBqB^hq z<=Y0OtP>|@xmJ?sXpb$0pMw<+(ZcoeD#YYv=kl=@_hJlkFy;_NDm84GTy#HQz4hjq zHgC?{RTA5@Rg_CPTBa1&#RrEx5<}7f@?=4qR|{Ihu-d^G2RuPY&2S6N(x;;dOJ?uP zYGCfA;D%SwGv9;yK05v%QD0yN%{6%u>fj__!r*7y26&H7$)aQUe)X)`?NSruDk~V6 zw~9Nf*tX7PKit)Vg<$gOg#fw&Achj#2c)CK$7WV19QNzS9CQ77iU*o(6TkfYDXh$M zS5sTt4!20?VOYQ&?k_%COAwQEOr3h`#9<~D;Xlj5t~e4fTk<2bSF-%s*A+{dZD-3l zkV~t-d(Iw^3<`8-rnJm{(94Md0`?N@tei^bR)8}My52#Wr6eqgiQW+(RW%(Gmy;Np z5l%2D4b44a(b2+qcZ3tG2SkWY@Bhw&HXn4R^WnK0|9#r4i(8I;T^XdPlG2{$*&Xma z0*e7qONkILDCU?1pWP9Eq4S1J=0(+L9Pg%x<~&r@7Znv6q-%!hDw$k;?;O28h+>-P z-EjFR^OoAKoGz2{{3*3m?Qd84sW3|$Wof?lVkWzXb3%+u?{*F|VQK+F_eA8}9`tXa z3yiirX3a3Vz$Pji7qHA~ashJ|c#Y9{>OI&?5s4cis;WQObz~vpICYvH(8p&%szWb2 zCB#=Hu(p@u=cli44Xw4dM+oeQQlcG+n7hONgG2uNH&E700K70*Sl;Mx1W+T)wzgpk zn~;!@^CKK1iY8RR3THyZFX0&9_)^W~N9&XaQ7OWr!B7c)aUH+LU;l7K^LO!=Rjm&I9v*XAtO*~x4o7@+|S1OUh#e263)M9~6!zC=t!@}l;{z(ono z^zU!0snhSJ^4q=kC;vP;`0?vk*$4g0#ZGd)&Z6rk-E)mc=rjo$v#(0<>fbe(<-aRWZ`7rtXBv(*puwg1(vGTUw z_ALAL;TGStIPqI=qwe*%!J=!^tL415Ha0}84Vg6#*pQ|^B>?#JPn;0IYhzq?g^bA8 zO~!HXo@bz^!@++LKn-NzhLA?rEHsO#*o^ZBx9&WG)hWnSiCaTf@^K|!bA|8UHPM8dia26=oQaNrxa* z$6ZPI`NqoTYO%cGK%b63g5O_LTp(Y)UBmf>`VPE#EHwt?;o!X!QsY%AN;7%mMsAKJEWq} zmKNPuqC7Pi=Qpo?$9+CcE_*aeFN=ROUp{S9E9+tI#{^XA6%X%JB5yIa0a#bP$${-z zO?x_b=X7*J&#&A@B5*g!Mj~_+Hb%T7lvhN8cxzqi4k;D7#DLxNig)JcmW(9ItMTN- zr)jX1?Y`S{GAk?Vp4}Y{$T@8CnsvH7U1fg6-Q6XfPE<^+x9JLVQdU+3jTSZQSvcQq zKEDqUJ@iT3#Rv_V=CezL*jQCGpHvvY+C4Ypq|0E|O%(>;>pdK@Nl6!k@iwr(e@RF) z?Zw$OgBfH7F*_2C+Ilxs=2L_1`!v!RqwhE(&h{CGGUo`FeaCnnGLc&`F%>J`3s|n= zRp`t}F(;>cQ?@DDqfO1$zAL3Y+qxgJ^X3D)argY`xC(3HU->krgHc2O!i5W}PuCoK z4rycp!r+tB*wiEf4gw03Xg7I)9331qv1{T@OlB{`(sfi5eb0i{ANT6! z#AwSzqbH|&9?F@8ma&Y-?7pMD2*ZB6#xn^n6>6VD+%fU>xWq+AieTM9BW~}_Z^!H*IsfeICTo5Z#ag;V}0Q8`#L{Pk3@68L>1 z_}M-B)!C;?E}$k|OI4VErz}>#kN@{Lfi};4Yb;0sFTG}J@PaI--thj=qcYg_=%TVP z3^4l|LNC zKGnHqUA*i;9?}hOEqaT41nLZm8}DkScf{2Y{UuMxNBj!laD*Fr+(c`Iiyk8{Z56>S z5L~O?f?TvTf<>{_>_>aK@z;t`*|zeQrMZ(S*VSr81BNB!rt~20Nan8Odq}hutRK6~ znGb0L2b;BYvdfEl?a!QPM0I;_MhXDoDy!#bC7j;6t>#V9ESGsYyffX%XzvIv*A)a06D8W@R-_mA30vxh{ zy|g0#=CUadb~ZK~r+Ysakc|Avv25@rcvYwTJnpgYp1S7SqD)$+;yYYdo24Xk3=dX}CnvgYZe=r9wLeO1iU(GPwDh&~0 z+e)vn}=u*J7dNw0FEN5n% z>E7lb5Xjb39w%m7r$4P8vQ>O-Q~eJ`x5mZ*rl`oSiDfkU@7mLYY@0SU z;0z`u8dj&sjve7`V)ZaBO+xP*%kwS3$N%&MXqsHVCb)_{&*e=$4p#Wyef9WE<|Zeo3S~Fq??-L#m#_Z>Ux}SwBGQx$K0iLBcZiF z2Md2aPCKe7TSH*nX=zeGj{z?E3;aWa`Q5;xy@0|L9`iH)KB2F`WdU|}fL6q+0qLZ? zQ}=MnLvngRk_oF*Yrn*?uJY4@*W7H_GE)r84_~~#c`t&Eh~&;zi>D}_K`n^Cva!uY z4uj_mtnn&mg6#q9I0 zit}h7JpxKY1n1DHA1>e*Xanxeut^YO0^@wQ=VWEVT5EVA@y+hgkY5S|g$prt1<71K zeo9ncUO$HYv0LM6EDXLs@0|KN%wBdQE5~uR%F5QsPDr}EMk7x0^tXD2)7s8xPQ?-V z;`PUwq?bLXmZmJF88fS_q|#KZUVNCDwTv=ff97j!U31K2KX+n8QFU|eo9b%Yf-0`K z=DuQJ0Z|{pAX91o;C^@bi4k{fle0ye2{3QlHpw4y#W2Xjlsb+jaB^X_8bkCJ{+f)n z^z*Z+^t(hkC;N6nmXc+ZHS6d$#9{((cY!7&oNF9EC6+j5_fHlsydmd#K$lo2B+;7YL zhXvTW)wODSwlE)`)u+TxoE}83ZxIIp`^rP**58|(tCudD^4{3k0o*ROgwqI;Aq%TW znwLZVWS9=OqKJqF_*x8H7R31?rq)A^z;Gck=ppfLlo%~Xc};I1x{M!z@Vg?XlhIg3 zg~%a<)Fiw6Z8q58dY`@5F5F%_MN?L~DcRnsQvTDz;vi;Ed%<0^O}MBACnAN5A<*rd z19IduWT##yy|MfYx*R-^tCudFDgpukDBM1?Y_XJ{D=Jh?#*FWe!e4D?pu2eIxU-3D zdws9PT+*&;CWp8E0_i*HRo^ac4?bP~6ML|6( z@&qN0Q!T<5S|t}wCS()U#q)?!5fpN0LXZv0vfqAb6_j#@MOEE5t< zU$&r<{PpU)qXC%C_Z7?Vz{iQL#lmdufwI&yJMYt8 z8gJzZ#s1Mz9bTr@kXOx{oA^Es2|#-Y7b-M`zkm!Gk$qbn5<+w*cw2C(d0tulD5N8fdd%b5>zP7Z8W`D1F2aeDJ$j8AtDPPHw z%4@fgj#?oVa{b1LoVu`IG%M2d#d42OjgTJUtB_$5EzGfd+;jU8E7v?cZks2p#Ot95 zqzue_;`d;sPsK-l^YA?9%y8SOVU1O$;@9*e+mF4{Bs&J<@nk3*Xn2L3>;2G2s2H9T zS&2)lCAHvoEbPba=ZYpovE)}1!535Rdt(61P1NL7ZMz;E{24=t$H2J3fP`3*Ma**| z{>-F$%?J^(PJL)ZM{=cM0FNEBtB>LzM&4TWnSn9Ui|@r)RE0erYBNASMBen{JYfnq;7&5X9)#x((~PG*v%0>rKxm^|)q`m|K{hpXNjr#s37yxwfUnu_*q z?EJjHf4wi2j>R@~zgg@2r%D&S*$m(uz%?`fWS}Ge01iGHULMG+K($6Dt_^|7sQSLK z@6W;Q8sg4+`tGICK5m#ZsQuI%jcQK62W4K?}bc0o#+AvdU{MB(!6)RY?(!y=M~6NrK$ zd?t-yK=2GqJi)o)<;$0klZlSvOkF6<+kR$s5?D3-C1jJm6Qf=I!cKML$-4x^}mi@!)JigDi_$j+sxY_wnew(?H4x}T4JGca3oULGIG6Y`khOy@4OE(flk zDE$)7FKG+kSDYsU9l(UJO3_9&8Qma_x_!RvHwTDtvkv!zPThNJGdp0JsJOg--;NkG z>Oi{E!J3)538W&P9vZ&s3)6`Ub&9hkir`oG@h@O$(9f^ixbf6Cj{2QsNo!VJoQ~w| z<)HEf!d2VG8UqV-lL^*?Fk)b&DKxhWtb%dwg<j654#jkJA+L%q^T z4+eFnTdiU}+Avp3-majVEwA1ktWO>GEDoaBhZZcwK{+DPnZI=BGfznqoyL zh`N?>T{sD!6*A~{1x)ASo&=4#k@KkZFvcXc|3_@^86k5uvVyq#motNy<0s-KFM8vZ zgJ7VA@Z_82bNW;|FAZ>6dKD&jU0(Rx3U988`-%ls-Jj5ndg9vOK)}O*GTa2SF`6-$ z=8K4y9DcjzW|OPcJy5dQsme`EiL-GguiV!|gj z@7ZI5^~*{gl+uodmxh1pJblIK$Vb7b9=}3mg#PlPVhI*I1U>cI+ckUW=zU^RuOrYi z2!$Tw-yT=~Hi|iP&94JLG9=H>oZhwkTbHYj$>?z`O|AH}@oD>-+S*<}-k${?^U~bqUe@_AVWl6aqR`?wLEX6wfF#5R*qjvnCQ4#NG>&tW&6p z2=imfRCv=rF_%v`w``dtHlbBdiz=IfxYI;=qE~#me6!Hx*~HHVqe2UzQd{)e@eARS z>g_@2Sm*zE3Ax*Q%*#Q=#7HqPNd^{n8lMp5iQ?{}_9)6`^AU<7Zi2kqRWhfOXfsb} z1&Xz$VVoO6s+`($TFq@S7=Qq>tR;0LTGca1gC7!7Er*Qbp@RokCQ}sNv#T&{ZJ-s8 zA#!!)H!IU3s$Cx(`xCx0#qEjahJ6naKVKCL-#GKr-u!PYvE~Pi5z*4W9EgO1iXU+WQ^t?p zgFgMA4?IoYiLevNBlxy-*JwKTeHuOYHk9$?R8F|qvk~|&X6n!m@ZK1CE$AIYcWU^5 zRPA4W&e>VkvPeBFCgu_BPE1J9HM+3UgK6JTEsVi3+xVT9A<82o)sTrF^Gb*88Io;~<~1tgbq^g&dgXE}vaXB#)OMf8F)s-E@ald}n`Wr!8IrotKy8Gh@lDaRnZ>O7V7soF)45@8L%6hY#QP1kyv5w@6b zQqe!x%W>*EU&eP0+TfM(D-^+qcUE=(Z$vKo94&#Q&cZoinD@pV&p4izD~-RyI%jvB z%eORof^tcdq=?AEvd9{PE{O1A^W?y=*4+uN?j#ov@`r%f| zx^CS&jU}3baNQ#w52R&XB96p}x-^BEgM)*$aT{69x*nnlk)!%6m1j4mT&Ev`O9JcV z_Lb%zTjzeX!s5au5gqPrX^4o-*a=v|s!;`M@=#G~*wzkXP-Swn+Ra!jG7pb9xdWQD$wU_Wp!|NC z)!vO1AC%r|1jbJ)2}tvr9ocGrSp4PDz2qJGfw znb}^&4APmv$eNF)xwr)xd_TGkDr3>_m0Pm&#_A8qfDjl0iDPmBhS|R$+k6Po$fs!V zpDz#2Pq@&qHo#fLCQq2cQc+b^Pq0{*ySJLxq3~V7;8{Xms!|yH=}V?&ld2D;t+e8I zAK+!Mkb}+cVr>RJaC5Zu80Zs^uUh=m5lxf2qh;TDFAjY0F&GJ66Wj69c-wjef~k5j zG1yi>r62kCkMrM8L*AH=b&6?m?I326&0Nfc;N&qv6tF zt*$@Cu$b@rMvv-W=iH#9PhG-x?+Qgh6E-671)(EABjZf#6+RZ9pcO?@Xr*TyE1v7A zWRyJ$8eNrg@eKyLCif`{H(?RoU#HIf{oVSb-NvZS4f)4|BgS1je;sCWP=svi{@!hn#cP{z5<4@2ua*~0G?R!C+bOQHxK zguFjdHo-!(L(&TyL?KoWVKpi-;u!KL+fT*xe5;_!0s+WRRfztHHp>zLOkNaWqn7WDHiELvPa!clue4|cv; zF4b~LS8m8)U(M0S(eYod#bh05_-Sphi3Op#O@~a>NQsS!)qOzl9zs7&_v|`FP27GP z*QRWgt97MK{Oo&%#I98yo&8hZzKZd>mef1m9Cgu3DVG3{=?9ZBJ_0BEV|&Tf@o)AS zm=1aCE?xnprJw7|y`Ta)t+6i}%NMl5>o>gF?VMw5>C{K}H&f^X*N(&0P`{hEd4ANI zEdX70VD}zCUz`ZzS*WlruDqe-?vGCM(VV@Zr+&5-Zk4#)zPnr8_GNL0EyEFB$)=gN zsPCVOQ4B`Ah4+}ClKujn`+s{U;TRF znIFz<31Rzq^Ops$rUz>C-<-vLoB(V0Enl;#>!54kiWCSi`qPGXs(WRjx0>hN)q8D! zjF)Sd_#UTMt>)Ly4ZUbS-ea_8FE0aaKan?rd7Sx=@E6aYhwG{^EN-*tcopf7g1t&{ zPe0G=GgsseI_!_gGG^8|H#ahC!_I~Lhk6J@cj5?5W-H_+q@`Wg_2pdbXjzO@wRf-H zC3fNGfgcNLL#4Y6)mQWDdt6{SzjIwNj%&#K03>Um93}w!ERs5h69-%17)sbiII(` z5>D5Tj*jNCQKHo#c1|3=kqBxNp982KqB>RMYd zV$QWIIKJR#Y*jnXcmu9WAj@o^Q0o87mtZtPT(=2r7y!e!(MO-%py`utM78m1blb@Uwvmjk2&{$?AJ}(A1L&!&S&E?}y*k%2X5B;{KuXLS=ikgi-q7Y<vs~+Kco@pzy+SO=Iz(qKrnC1o7T@Iv}7^gGs00l2J*%x~Sk5b(Kzg)}qLwp^1JW!7lrsMhQ zsJSMeTa8MmnTxuO2=Os^he^X=U4FQfg)Dy{V>EaSP{jK&F8&n;e<~F33#bTA!HIyd z$q=all-w_D0D%+i>LMM|xTK@Z2mYH`fwn;)V+1COksbBD4vcMCQP4`3bq>49J|eFN zY!>>WzZ)Xr&J-9Cn z!w{=^Vc#f9hUYLy1$-|32A#J(7Q7cc@$mY-&CxnZFxz^V(j~{a8s3{% zSXM#~qNr=!9kjF5lB;X_VVMHxh5_bvnB7p9Qxy16p5v^wgFYI{HFU(S9=DajdOjT! zZ88mEpm=d`a~nb)4Jad`x`as^q(@a0wq>8%>9(n0h91Dp zKtpgzmhA+if~0HS(_@p91mBC{3!F_1(RoCBZpAW+f-ialw_rKZ_vrzeX&(VbqIUC> z?k4;$gOj%SVTLX(v>vBL4*(>@rj5*E(SpOOj#apvhcHL(LKS%l#P;CS3Q!9Hz^P2r zkjOAS)^dMeRz^Co^wiaWAvQoviO>=Ou!JL<9sw6Gp>XrzrDI7L0*U}|3ehVP9_&ns zbNqx}ly8sQV(zc>(J9vik4N9t^(7F>kk}#)_oO6VP4V!?u}qwkW2H~WqWOy}rFPdg zL+4WY4Gjoz49I+s?t^5MXJrOJLowAr+~&qd6UAumt8h7}66zCfpN% z@j$+4i4W#=hV1sWGb)A>7D?PGZ)-b;f1=q;HU-XIC`Az`Wpu%c=}>=e+Vm8Ahs+mP zSXcl>Trth10ovPmpN^N@!;n*ehY^^l?{ZwpPc|+tqI^Y!7$CQW8-c0ujqiq(qDz6- zu6;t+iHL!Kn1pGozr%XeTu`t){qeHkzwJ#W@lm%ugj5JlWeWPG=#o|1WSv4sPg7*6 zx8hDb9OCLmOo$1te_~=HtO{P>AuH*4{UK7sTLOF`xFvu!;#R^jtH85{D2S3QWk?<8 zsVjP;_89iV*X#>cTsh|@C^Dc)?fZ+UAt7IQ=f4W!bT)&mIyu(^L^T5uRZvhc62NDy zDLju0C#yQL{y z64Hyvp!JdO;l1!jRjqqb_8QtZD0-04f&Obh`R9j8HC9&9Rl?eWQ3)|uA-fc9#+s89 zC4C%(h*Lx`2iRZ&oah{8_~F!ob#VZN!QH zJ=H&Fs61UT$Ff5ZghC8}UC?P-8G9UK;+X+k#k8TJwr>~07XxA&%UP^W*jEAk0tBBJ zM5Qn;0z&u3S&Cmeakw_kJA{)X&u#cF8BNX{Cyr<4b6?Dt{>WV{`zg_zF&QK08d3lP z7XW7gp?a&JU;w`2K2A@lTM5g^7y>?mMVunP9@I@BN|yfEg?|LBb z`iR1Z_^|=5OZFWAJJ)X95a6UJi=qC64Oas(dqZy=|8?2t{;KNg&pji+IUG7wM!0t5yID;3tQ-fpIea|5S;tohm1ZIRF^%YNGe_ZoH)Bmsl1nY*(SqkRD7>*zTcd0Zxh|^({#}MSk zdTXe>3j1Z5DMg>pz5YR*iva3)irqyF(}6_>7|cO!36C%)hG`tR13&jt8?>m zq)0M)(vbAwTmQK8+xE*u(2B0dOXl7#m!Dw-_5$Jqa(E&Kx7s`D_)FtkfJ@>LR@%KJ zfx$8RyI8F}pfNLW)__tu-g{PXyBi;0O-vAZ$2>JBSoSj|`Lj zM)2ej%RS^W*Ku(@A==Ws!=7^ZNhrFU3&*^WVj~TN7+4F4B?M9oVOabJxtoWo>grG_ zItt_igu^~#q<(p150M0hN(=Ye7_$P87}8dtFht;-fi!^Gk6@_5KHIp;J83PP($PjF zeOY)#=6Oty+?SugN+UhOfX}we7DG5y1u_O?QNpE*oT)gl5WgR!q-2t>2m{9tV9QgG z=^`tzyu4h4RjXHnAEb?bh2N5* zF`Me>WRe{KtpQjamSj#(86hwzOy<`5H?Of-+;cpovYe|yE_)0lE5TSpy##_*IGEIB zDVjiso1^pqCM zm&S*W9u-E2fvRFP=)_d9e#j0BE8Brgj7w1AvUs!UCdwuPlYefZBo=?Lo@a zSwvc_3KGLG)j?W;f58G=TlOEV`s5B6|9s1HO#?9NF|1qAqIv|%8Wv!Yb-vk=K(e@| z7zp5w;L%`4b{Ljc$iDF@-15HvzNH8uAL|Z08r;qyC#UE56M%6LqbT&O|0LalcS_nn zqCY^EIcD^Pj0*S{97O$=fOJ9bHrWa+QBXtb667zT&7Fcg7^+SvQi|!IABuSFty|aH znnC6xu=^vE1>6g6J2EFn#>j}6FwI|R5I9>=j3Sj{@Daa)mh{XNkMOs)}s}h|ooGiCs z!-0zgRfx>L&Jt~NY$cvUCV4IzKn9SkoT!c9Ca{mt&S73nl#wY)4}bRc=>Y*pv?gFT zofcPDT3U+K%jBOaHzj)Fpe7C+;EZ7iDs~EuS+e@JY|(d<<+l9iz45+9%7GLV%1Q{u zZ}K+Qpx1D%KNd=h*R=$ptRoLzUuLTnw+lB^5rIyh_nr(KVQeGqpF z1wOp@Hq*sv1ckO1(`Ew5#K9{9b4k1`q_v1CWCbGI0AvZm)ToLkgyQP98NUd`Xa8-Z z_-sEM1vl$m~2-;b@a4| zWD2T`{(oqf{E?In=UgCLlYnC)D+B$7|JH8Np~Z$Mg@I5H9z*{X?-^=>cBfC{u)TwP zQtJ1JLfQ1Itwk;8Hv-Q$%t-+#1NvctYx7bj82VljlUzXOv-xV|dq+P?rVXj-Fop z!M~3u8tK*L^gjnSH-mmZ(n*?~Hydg>6ePF`@csA@E|Hrc>&3=k zX`^cNI@HLND}QsS?|hrLSjQww7&w5aFi4r8HR1_MO6!<76-1WJ4N=qNXJ||8Eq>YNg9{Cs!ppmMx-oz*ZV04lW z<7h#jfTY!bIp~LS5fS038qPD6fawRtbHXY0y5}LBSH_s7k)9C_3D622VwVD!jx`bQ zEz*N5?d#WvAZ+eaSGPx&hDDF2SGo*C8_TRXi5`BsytBtifl}a+3puW*$S<+{HL;mM zr@L9-*JZ8w94mpa`BGBU@N0xt27OE-O}8976Y+&A4O4O8)Z=dUh6Dxa;r~SJkOa^S zKZ^|R5eQhQsN&;Aq_L_<3kB#3gwdOpYzQ;xFkwA;*J9+4LD@f{$6#I#6A7tvJ(?(t zeqmL9Cc~Na>r((aN6SI`Giw$qL3nB+eIx!P8iVQb-SYtyg%ILW0TloSpUHV`B^W~} zV)xKZ#**9EBq>>2U~5ZLu4Csc5q*QSQyxIt0r3LXdAi!h%s!Inh= z;J2i03G!)`qQ71fJ5R7uX8EDk1@-eChkbB-9ftHX0sj)CWT4(q9DhQ!D&%sl$`Z^E zEKPDg;Q2qee_wd9nwa&+J*L4af(N;r_oEk>5JK#;H8SG|RthG4Br78MpnJu*1lWHO{A zwKO&1!x6}$xDT2fB=f$f9!ivzQOW7)>)#|jjpbBjfboEV=EbCu&f+m*`0}pR_ae6c z|2B*%lF929*MebSf&dHO)CTZMyPR_)aZD~2^(v}hdjlG_0w4@Z^cDhU0oy_4S2The zNtj8K6^)KVNK{b&z+rY9(6;+_EXB4agnKwl8^D1Zr!iE#4HqjZB_Ei`(>2=T*2OB;h!UpGTImSYI8!TQe>gz`btnokl%g7rbHt(Wg%GqziuCMpfp?C!L z-Hk9<-HT_10)wD04`Z|7=16$QypK7I`+suP2J}YIjlmHJ%Da}V5~cI1qz8>0T9>?* zc!zrQA8Y-DT!vb#j>DVO?l>P%{3a-+l*8}lL{<~Ya&O)QWX1a;_|dN2mFs*L8=9?r+>Xg2)P`F2RBv z0=_2&Ry%$?DM|pHehDu@fG_XwzW1S(#48h%ZO{uww*@m_cL#c8k?InsdUBgk-^G9*hT_M zL|&Onpt|=IehhRViX&PS?Ln7<)Z)I>vt*)2^G36abP+Hd(?NNP!-mM1k#X_zDYmbN zmXUX`Gv)d+1*n4>q-ry(dcSt*y9u$N6r}tjh|>QgfH?n!INSK~_Wt>qR=BZDA@aYQ zQI6JqG??dBatxiW|APiAJ{zkdA05nZGG)$D&-ZJPf@T zEh^bpijZa=LKzRO8Q^29QS1^&>|gK)KLjm4uU8_7m zu8=!6dx;O>)xugmlqY93aZm3DLJ=0&Jzr{0qNt`W|EC;kbi`^Rt}KC+vY$Nj%>Ze? zJXJ49Sa-;4@QMiybg>3YIgiXhWpSsTKw8nfq=o^||H)3Y^O3wmaqbO@9n|*-#Kt*i zdHYvc%AttBL;2_0vuJ!nJ5&Ngi{aM;1{FwO4{<|mBsa|}hRUD_> za*#17(dho5bwL!;GXeVq%gOX-Mq(P=lqm)Wo&GSSlW7*1XB$N`8 zxui+8g|ww28dOLs4QNuTb3ZHlJ@0$2bG_Gho$q|#IqSOi`?^+Z{nvl^4bOAm_j5m- z)RmX`AWkhR2ZWuK697WY><4*oi5d*&Dzce;chIJ(IXU@i*9?H7 zygXX(J=NKcHSBEw=!g*KVZmV??5t?ORx3H)$3wx-WMV*RRG0y|585N5U^2#MiHldL zOAEQGpJng5hO3~3r|$Kr_d0g;=nI%UV!1)yKq?((%4=XbOsocszBo8cQ=uu-6$=cO zChmiwiYr&9lO^%Q_!x4!-z)87Y(&r%dTMKnEgsMd#N3m2U~c;HM6MypwdchFOcT+C zLVV!XC|%W~bP(NS<^}Er*bGc@a;Sv8bfS`1-VzKjrcwuhWFMa#>b<@UrsxO)q5c9& zAu}&fD*ZU&lEDB?QUSf<NMSx~$!HPd~W}Vt88H~A^6ic)iH-=Qr!;rUDLap)N zVfV9V`FU@b1M+j#t9|_V2m;K>izXElcIa8*ybyyw{0x$WI!+V$08Ru;6q;gzKTCAg zdknDT9|M1`K2N0$%#g4XFJf|QB9O+sBEMdgu22O&UunxLHR<9GPpJ0sRN$XbfF>#z z9%DVgc7jF>M__a?xj8Eb3_6$a>S0-7+y2nHV@2CPRMvvB#h#|&>VW0Z+T9U$HPp+S z9k7^f+&Hb3n*%Enu8*B%wHTApJz`s39Ko!ktE&bYDz?A^=>mdng;y#t6%u4rJSyY^Llzw+gWmO}57Z=oe`j_+=eC7)sZJAAyy>;h}-B zP!{b*KtypXz>}O|&oix^u-_QKBcy{g0VlYz%58?VqqVx-=9dfQczd zSPQ73j%}-kQ4~K7;0X$NIdtQTu>w*!#Tm~D5Dqh`nwAqv&@fql?!?K))(#FEipIKG zKhpq6IFCg|$ufnY>|H*9R0N#vOC-rZk$J3&+S)0ZLv^Us?JSxYEkXg0p$PkoZSpSr zVR|rs#kvOK%@i>>wkCig&``-FM_U8@`cX9nJD;J7i>eJjl+a+6WSI~<^YeEi(5^-u z#3hufgAAhl5Ls6EHwk{Uq({~C$;k{1{-YOw#vEFH5Yrs!(IJN6d6+g)zZgRA4jtme zm)R={Aq)k#k3K^&Hao&D-fHVvr4heCKCW*;8utLpH*T~qFP-&aQFu72!4X0sOvuUq=o8pvL{9q08+?L=4F4D zl{sKSaocbbFHF2MCvz4O#20wHgj@ihG>fnSxVsoownOxH1YIN0d0t0mBv0+6qy&-9 zqq_5ilwoMcMV&r%YOn%92URBn`vby)ecaKciJ#DnqVJU~5mDL!IeD=IhS3*bn?n>^#jVKxsgvGZzvS%zj6xEYZL@HDe!{8d(c7eDAcRuoRAObiK$7rH4yrxm3 zp^I`{s=o#81cWPIkfs7-ybia9wsR6k0r0^BWP(`)4vy>Hz{%+7{V0JT_RnlBi2hKW zMGGTk3UR?3%V05@#Fe!|dZ1*WWX(_joI2y#p%=Q})LdbgzE4Df_px578Zr&4=^>r z!wZJZ9LnHmoBY?LzNV}HE{8wxji z;*+}MpWd30leBy;k~TJ6e0VuGgd*F$(IWBZug4*mMtXi|Ij=qs`!mI9Hl9`H*p%2u zlna*zb$+>^;2&R@3sMg$hfuhIr?3z6=xLaHY3=CTc1t zufGIpH|lI)Sc2sOvl?0-I&H1{;Bw@or4LFOUIZ2c)6>6?S>AK;BdSjRzTc);Y9^1g z01^_IM&f?sX@ZCQW%8!a0A~0%b$0* z_=B~NsmCg`K>`iS%gO#=pgXN=0Oc@7Yu0fv`U+eZfQ}%uF+eFn(0ox-Q!HmtYoXI4 zgE4IRQ+y=21mm7;@-gF<;%brJ%fvF!!*&2H%ad+zv{Ype7IQ>_2*l92F9z_`YiHSF z^1r}lvT*X2w5-NtM}d4O2$D1CJB8g|kC%a-H?U|H$F;WD0?}uXKO~XN1VE9g65zLR z#ltiTLPMaCWAx&Nl4CF;S~6n6^SbfnnJ}zUswxzU0DNsimuB4I;v)Dd12fxZW|j)+ z17YWLjvu!Ek%l23$v=O=&!Ovu^@5lVKpsm0_&}o&{*H%eDufz8Z=9hfRt)q;&P0|E zq6P9Eu?xdhFcYyum!ipg%N;d79!yq(uvS0;)^@748a^M$YRvr|)Irg1VtIm*r}GFmvX?}OHU1;&@OPT=^bwe16{YKG^?xBM*tgyX22N8O?k9`0$G zlcGxcBF!T7Ny3d z^oPls@T^(y%?pi+$FiGRXOen8bwu5+a^)N6$WhKU!n`X23v~%x5q- zr5P=w$WqdAXoSD$zpzAEx%TQH+9Mhwgw43ffs5i>!o`qi0SJVxy&Ag{VWGIA*}UNl zhIL;bco2VqAkE$5aa|+k2Z>yUeTLNKuegBQ2D7+_^R#&QN2 zk)@Dvf`tmZw+sN3WXO-3(63y^ibi+pU^SRjJQ0dgz)?c)!&Nu~8j>npxB+r19B9t*Kii5PV11zo z5jUL9Tf`X>F97Z}&`Ltzc>(E5+({|~zlz4(JK@45tT8#79>BZ+kq@~LsRRzY{`u&U z`j{$)DEWX*6Q8`k`NT;P_!KgpuYXeP64tehEI7sO#`qV;*mgOji__O878o%e>6xg! z1gUI-$Xdz*&rNVxe%UDHirvJ;736>SM1HjC@@H&Hxs@@H_$39FB+>|J01^pQIMT zcyKNerurO=bei35Z78cU0cT>mYgfG$cPSpXnF)iDD^0UE8C{gf!ie&gA7f*%Q?k3c zQ^tUF2#CGqWF`kE>lJKnfbn(^ZiJ8%lsipZ5Ug9E$&0BR5HY+DKa*1Cb z>lvboWvy*`dU_*cIr^^@40LsMw+gnr{{(^^uYYsdmfN_9?;+%W2t1-j5PE7uGORDdhPwycmq9qRe26VQV>KoCa*yVN* zaBl2Epy#(EpoM4zR7LmQftkX>X~-Os1_1F&AOADxT!W{V*VuV^>}cp(S#V1pz968z zT+Yo!DDUC};PJTl#OIEVFZKJkdV2O(dMpHQ3cD7VU3eTnaHpXgc(94BZ7Ti1q{0D< zWrh81KZ~>6Q>Tu%v;uQWD*z>K24$Rn z^Q#b+4c0wdmw7R0w21S^E5t3Ur@Q;oI~}PqsqMZxp|YD3(}=)MTDcjUk;`ngkyJDr z#DYiJInY6DZyNWskk*rNG(JdS6c$j4yJNT+h|4L7#>en!2o~FKo@_LTk)?jUkW)zb zxj;8c)I35ZGAPGQE06fXD`-VyD$`*GB$K@>!s+3Ms z5p8|D+?@kegp(6ROc*Kzo?X9woues&&OBM|MQa(&Z3* z9gyH3pdtmF9~CbkfP_Y3%S|c4lDl}u#MDq4fRl9@_@newrS;R;#fge`$EXMt88!tM z&;$-1afP6U%mqlRpr!RTwF}82Kt3Zly+l*d9w{ZEaRU&6A95efiNrRFsQ(p-nK9%_ zCF>p>mtGS==1^3fKzJ9nEz*Mmmx3n14MmnvHA8d@4s5oBM9-JHxAb{LB((QolV!d7 z6AO7$a6@TH2_c*~6NhKLXU)(0!oX9fuan{vd)gAI z;@e5t*!)!`eG%0WSb+_db{9N>%dUdVR&!KvlLr9;5Fd<^N<(3U&O*PrJFcyd-tq>IQ*-hmTrjxh>zdQ2o zxI#Zj!@l#J+kg>)ElJ+8sfC4Flqg9s1FwjyY z5F^jDA`c(#c*rAJTQKzYDk52;>@+SHhxQq7*f6~Q*u#L~@88LGmI|h@47SJE35tkZ z#_%VF4vr^TTlgLF8xm(Gkab7K?RRt}0sZJe4$3GL?;HTb0+*Vj4YliZbV7gj zrKhR8D7u`c0NlA~MgnYb%-dHUzrvR4YogywK+%SHuIjR+j^XN7J6#7fc?N^`t=?rv zl*mfwco+^f^VP3&eOGoAv}()_pE|F!F98!{LtP2`&WXkz^gyyiqJvL`qdo8Sq!&v| z>!K@db(%rU)V86y@ISYLWftP8zVCU=Y1697tQ&<}y7yh8MONsc!}!E`++x=~=GrT* zz!ap+SP-@hb@>W~!xvGbBtLCUv!+@A$baNxi}`YeS#|@l(xr zcK+($_mGDSI8p+a4x7mu#-BG$)$c&A$2HhpRhwxxKpjEA2c&bl+_%TNvL4H;k$7gD zYPhxnE*IyzK){qWbJnbjsOjo}+CL&-7IHN0fRJ>ih809QfUV1f(i-}{eXGHICf7H2 zonRJ?wc*ytCMQdI9}>1>>zMJ_M;b{OR*xiQr&_sb<10B1z>Esih{&mC>Yzhv0K5yA zEn;;AHsn;&PkwJt8G0jsQF{^gKbYpu68Mehajx5Y`pBrW&v=SQD$i@!2g>mYGQY$f z3JV)(^mzUyJVz47U7x;`a6C%)Q>kcIsjh*i{U)j&i!_$RxZ4cPPQy+vRD!0xk zF8pEX{D)yMa7$dYZmN8`vDWuA=n>DVU!ezbE_lRI>^J^IHMfhjL!m46qy>3qLM`4}d(UIiGQbvBJ35P9q z&+Ck6t*2wd1`5bcp(ka@Gk#5()D&F{Of8y)KP zd7`y_#}2a>+<&{FkD^} z4lPI3m{GLmVEo&_ZRX+ zNr;qjZGU5~8+qywdEd_qq0-2feRu*pw#c z{e{RAY|ItliwGMb_7&|P>;Lx6%)#L@i9q+1F=-phlsubp=~4$+W8h25`BA4%36`!2 zYBmC!1u4!YsQ50!uN&GyBfs76Puw7Z8f0{vtutWHlQn>ZMM-5HfmvP%_vvk?@CkXXG@WU(W1ooulkxZYk>j`3DBz+x$dUJw6C2i)@z%wo8Z{&9IVvQ;reZyN;Fs0Y z)g|6PhE)yL2|I8A{iu1F2o=@tmY0!>CWds5!@^LVBODY80L7?Y+(oP?Y6pn!&Infe z@Kk&Z%Qs2qOngM*m3Kf=+>o6mh{6>@i)+L5?{`4#GE1*Kuiwx zwnv2!oT3Wkwd+D{4UI-eI%b3zO>0)bCcp*$6VP<d`#j%hYo1BEih ztiz-{tLUEvtp>%Lh@<&`jV~$dm%xUlV$`v~6%ZKtjw4ieOUn4HT@F|Qt3BxY?U*#O z#^;>XkDS1U4$1hyi4;HfPWVyo|0I5) zw+n?(uyDNyt0)ujBVXemZX=;1D)VsoC(X@P*i)6f%tyX|UyL0Fk9yHmH#{JYM5fS~D*SF-LGrpQ#cm;t{;x0sMM_L!1 z!G5GXHWmK(me~b^iNGo~?#Uz1>&MJpymV=WXFQO36=hYl?KuV2m33#%=*UQaYougn zbjXj?^@pQ(iyPoN$nmn{;07!rUTCHxw#yqbsr2?-Jf#}?c>>lX0$h}pl|K7rnF!&hT9} z@&b{WkW8q?Yt>Fj?h3zu6d&vHDN<^hZa3W5iiq%C3+KVA9frulYE?b4@`MbRN>aG( zyUq_MK*c6lP10FCT=yG?!fN5Ha~&~az`7vZ@AZ;_eFrnW!Ve!7^{;?TXYZ2ahHh^n zlqu;tmY3_^cFZh&yXZ9!vS1#`2^m#|%Gf{90?--7{&3h;2^v%VD%|XBK`{48)wfls zSc9Jaygl@n6wOi(3@9IS zae8nYiG`I_?=~+tbeyj#7x7>S7`c9L2@~)f|KXRtBnEspdHttPeJCw>Nayik*ioiv zQ@|jMRkZqVR81{wvflY7M5z)uI|VdvwZvF7UCqN=kcx0kS~y6 zGyj%6!ha{H9EXbbrqr4b+=2!a)@k&zTHfeY z`?z$Ll`6ceOPl8m_4oUBujv*?0=m@9V!hucJo9L7y;Q{CKodT`Y_o+lSmn;Vpj-AI z4H~f~eYz=GGPDCE1a6y>)PRlsUpc53sQLE5ujIbX$0xTJwsp0)@AJL$TT-RH(`wB> zu~hLHe-i>hQ^i^`P%H#h(M(&C0oQ{BPbo1z80 z_0B6(R;kj;x@(t{!<)XozTij=rS^!N8J+L11bKb%RrPNM%JVgkBikhd1utKwXA!P)evfcDet+Q>h;j;=|K6p1jWI1`W45$PuSXh-p?V%t(UUL^ZeAL%8zDk zd+kF;8(x+;SZw&3>7roYS^B%;%3YFfZf<#)r1x{xzBDecv3LTfVEybVTyAII6-vj& zt*DzBwSLEEg>o4_$<+Y(@%m3f_AU+|VR@*#`cY)V3jOH!Hl-16U-}ks2p`<%;OMyGjyaNL_Onyj^(eOh;qICW>>{iB zb3o&H4y$6%q6!aFgE8m?Hc1!n7o9=&yDoJ`M~)nE^}RnlJj~Icwa_Ng+i(JV#hPxB z)N(hZ8`v=Y-r}|T3?pi zA}R-!hiW&L`c=!G{BK5PL;ips&jT(^6r1wx_w^EAI)BeYNUH)Qp|oP|?AdOoR=q$9 zz^C2j?BwKr*~ZMm;y@>FJNZf@jaV|HZv}EBWsQremG(6d8aFwG5Lo0Zb`EPOp<421 z^PU*`A;;^4$8KL|<|PTg4>Q+#z)2atpnDZai3D5Sg`w;mt&ZPgUqaOzah z_w<(NYVT`E9&DWEbL+L=hrgsU?I;wksMQA5p*v+-T3KK33`s3>0nL8F**wFipf_$p zab-lDHZrh=&D+Qw2X=d<6}z*x6L&1%P>6adGu8?;J=%WVyyHyyd&uKA2bENz*d3*} zYbpi@1`?dCfXiCu4{`}u zv2=$@w%b2H2}J3OCYmeY$xxSr>e}#j`|MTM_YAh$qa zX>2Lu!HPWV*7yw8_y9!B&GD;D_&V1ul?n&eaay7p%$PuA>T*-lRMw;-nAmh34~IKZWMaI2L=F5PYLP(GvdGX#GXNZQ>c;a|LD3I~=03xcyX!T%9RI;XoK78Nao&mhd0rQ<&>?N=CtxXy4UzGE<7dl?jQ>RN-p-Yev>5Hk>2x(BFqTTHtn}ig!D%8~T;aA^I(R&@Bp0@&vOSu6F!+nl`=YXb-xKsjd6H9>txq!0umnN}5bFJC4E z$MA7psB3^QpO6oP=owi`($WvxJOuBPpEcj7-c<{)`KDq&34(Gsz3w)$7Wm7(c5IJG zNlC#KXGSv4Ng=HxRj^J!LrB)p_50o`S{xEtm1i?yR|FK~+mQoJH*F*B|4Qzt?IVH| zEErVlO+SF!AEO$m)%n+{l?YKeHTRywPz1S_n09c!@%$Jl>e8pi+V|N^j+w|%zl-B;IRthp#gldg`22|^H>`-Vqp5QA= zBl-t|fqyG2Gt~Zs&g(7&(>cSkl`|2!`XhC39L!3`uC=;1|NXs%_wueHM5N}UPA)Fq zZ&-m?vv8R78@%Ct+z90)3? zqbQi9dbukF1x?FxvY}Lj3!ZG)t^xS0)xj|~8w6zBxDkfPJ?A$iat+*izQ@Gpn(fe9 z%xUh{m^Z@Pelp@z#>x*2zUyz_T7rBEkkHOu2aFIOe;1p{Yu<`1l6?((JUx7Jpp4IW zHutq8@C$0AVpiD8b5M}Wb43uUzUE1ch>Bc$^kjc_!N;$QlB<2zxU*2z2Ez?ujnLrz zsCGvypVenI{Hm7@W#Bv1yN-b4qqZTfUs+d3^ z<+cr?XpQaS9x|@M(>m1XtF~e%R{>mY96?|O#u-b6XM6(C2q>{1rY)u-uB%B58ZzD< zawRp@wm9Sg-F4jBh2J=b4Tz2$O9xH5xoBdnx5-=PV|u!50lX!#RdMsAHnz8}1xz|V z);wW>MjA8Dyt@=1|F!}#DtX`_V8)Kqci&)FYcQx(EVwG4RF$F4GS(j3iiFujUq6CE ztv1G~{-)ihuuMZn<~vr11T6^cA4z1%Z6oKwoWcJ7PY5-(0nDMM9a!dv8^646Y`g|- zKnEyiqqDwmKf8THnJcN#Ks?rfcgZCRxQAc@sK+db0R+|<^!3oOhXjaWbGmQAMNYtk zT#<<(x!=FOVY78kODghIs*M0r`q(9B)O@uxZaWsh7l|tSNlBGcUx>m?oGew6vTcJF zE-WZCBIpVDDvDU2AK-ZdE0C>ts#r2I!L&F5T{7Rm40rXxT_Kq#jN>n%Q>P;+I>hK{ z)-AJ0tpy(;sLCPCYs@={f~suP#^K=`laVti8$ucKM?-UNPbwrKN#mE)`g}T*rEwT@ z0LE<8$`PzSm2?2qMm4;P*$%|@ggd&pG(%9;WIvj`jR%_oH2<|AEj8_@ML~^^o#{oP zj9^KOOE7>Sa4M$2>wXFkfW1HiaE$ZNViXHe|3?xmSX%a&ocyu zY;{y_Sqh~e2^w&NFaz983hli2p<0%_JW242pp>*3u(Bc^1UnT^&?vUU0r-Y@0ZiKt zWQJ;5AcV+yqqT6<3`O-g5{Te{&w(L#6bd4nfeUmChY4uU1Tc@Z3YBL#{Y#LxOyS`% zTdr;M`SnfG0$;EbK)DVabNxOS`gnOE0wE6~tVAT+04Q2;>l`HhtaEc!$2+pxAHja; zY_-%)xGmze@Lk+kvlugUXKB2|S_R&c{1(J_4MGblp;>KfZ2Y{ktLEecpZCxML`q9! zWgoS+ft>LC@c4J#roon$mZa`5@wyW6g2kxR#$#E2xnZubaR1zfb|cmmxSIsKYOGXM z9WCSHRqC!lj0`gAMT?9eXU~3=AX4$w1v@maDR7bVVD#(*Q8QA>3bu84gEb?hDk7JM z!Kaaamh$0$CsF!0>ZSjVKZPnxKhI>8-??{>h`NYBx;r~BGB|RnR<*TjYe2y2DR3?* zVM0P-wK78yX8XSOTYfhh3WPc)i--B};MbpEvY&UOw zdI9=le5k9<{CTKqv*5<+l~38Sw*0r1pNGbD9{aFWj4flg#uo^F{P^+QAD%~UO&-SU zlmFnTjZ}Wm?58|*jQm#uip>I?=os#DFD)w;E=>%E@7b(6rRHd!lCI#TnQ^x`>Amb1 z0h(PMi@4~6328%e3iM{5Sg*x%f9?6q?9ufG-LWXL!I$#~yF`u0rqP*towm$qq&JJ- z7X)j*A5ajq95O!5Z{khwwcO-4f9|dQ^tlT~2w;@>VmuA2cRppGg2u+XX%FCIpwQeS z5ZpQA!gYn*?OVj{cKM!i!-w$OBNVJZ@gue&OYMc=hG4e=i2rz5wsLI zyxS|u)REq1xU@-T@5@cGbF;oQA=44`bPm1Q_-b_IsP0}qo)Y*OKS(S8WlZ};5DISa zm!o6;+XH_1dw0d9%(LtFMxqnrrs)@9+CzU`e!0HCNi}Tue2Xe@w-VFLWDW?KZK1yu zTW7xVNj*A8^tac0`gdecv{>x<>Q8?V;p6FV(g<6pzr%XPx30SOJ3FuUYVC5)fTkVa zYOBxQccV>P^?A$l6^(ZN+p!xRt@AN6bB-0(nNJTb)NEj*zj5>CrKasCW~(m~3|0^^ z`n`X`;OY57_5l{(+cZ_;cnEKFPtshGpWTPF5{ewMi^3%hc zr$@xdWX0UsULBb5!-ajT^W!&fi7HHbA-z;pb?DC0kY{ZN`~GlM)2r_6;&4ky6YPW# znh_e^6?~! z8y81=I}gu)J^=kHUCW1W;WcGgL+C$v!2Nu&uLXz1sj$4{XP9!NX|51Gu*U_m1&D0Of)GjQ{`u diff --git a/androidgcs/default.properties b/androidgcs/default.properties index e2e8061f2..46769a720 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=android-8 +target=android-7 diff --git a/androidgcs/gen/org/openpilot/androidgcs/R.java b/androidgcs/gen/org/openpilot/androidgcs/R.java deleted file mode 100644 index 31e90ffd1..000000000 --- a/androidgcs/gen/org/openpilot/androidgcs/R.java +++ /dev/null @@ -1,31 +0,0 @@ -/* AUTO-GENERATED FILE. DO NOT MODIFY. - * - * This class was automatically generated by the - * aapt tool from the resource data it found. It - * should not be modified by hand. - */ - -package org.openpilot.androidgcs; - -public final class R { - public static final class attr { - } - public static final class color { - public static final int all_black=0x7f050001; - public static final int all_white=0x7f050000; - } - public static final class drawable { - public static final int icon=0x7f020000; - } - public static final class id { - public static final int objects=0x7f060000; - } - public static final class layout { - public static final int main=0x7f030000; - public static final int objectbrowser=0x7f030001; - } - public static final class string { - public static final int app_name=0x7f040001; - public static final int hello=0x7f040000; - } -} diff --git a/androidgcs/res/drawable-hdpi/icon.png b/androidgcs/res/drawable-hdpi/icon.png index eab1fc68fd7ad531ac025a53956f78de8d4e5180..8074c4c571b8cd19e27f4ee5545df367420686d7 100644 GIT binary patch literal 4147 zcmV-35X|q1P)OwvMs$Q8_8nISM!^>PxsujeDCl4&hPxrxkp%Qc^^|l zp6LqAcf3zf1H4aA1Gv-O6ha)ktct9Y+VA@N^9i;p0H%6v>ZJZYQ`zEa396z-gi{r_ zDz)D=vgRv62GCVeRjK{15j7V@v6|2nafFX6W7z2j1_T0a zLyT3pGTubf1lB5)32>bl0*BflrA!$|_(WD2)iJIfV}37=ZKAC zSe3boYtQ=;o0i>)RtBvsI#iT{0!oF1VFeW`jDjF2Q4aE?{pGCAd>o8Kg#neIh*AMY zLl{;F!vLiem7s*x0<9FKAd6LoPz3~G32P+F+cuGOJ5gcC@pU_?C2fmix7g2)SUaQO$NS07~H)#fn!Q<}KQWtX}wW`g2>cMld+`7Rxgq zChaey66SG560JhO66zA!;sK1cWa2AG$9k~VQY??6bOmJsw9@3uL*z;WWa7(Nm{^TA zilc?y#N9O3LcTo2c)6d}SQl-v-pE4^#wb=s(RxaE28f3FQW(yp$ulG9{KcQ7r>7mQ zE!HYxUYex~*7IinL+l*>HR*UaD;HkQhkL(5I@UwN%Wz504M^d!ylo>ANvKPF_TvA< zkugG5;F6x}$s~J8cnev->_(Ic7%lGQgUi3n#XVo36lUpcS9s z)ympRr7}@|6WF)Ae;D{owN1;aZSR50al9h~?-WhbtKK%bDd zhML131oi1Bu1&Qb$Cp199LJ#;j5d|FhW8_i4KO1OI>}J^p2DfreMSVGY9aFlr&90t zyI2FvxQiKMFviSQeP$Ixh#70qj5O%I+O_I2t2XHWqmh2!1~tHpN3kA4n=1iHj?`@c<~3q^X6_Q$AqTDjBU`|!y<&lkqL|m5tG(b z8a!z&j^m(|;?SW(l*?tZ*{m2H9d&3jqBtXh>O-5e4Qp-W*a5=2NL&Oi62BUM)>zE3 zbSHb>aU3d@3cGggA`C-PsT9^)oy}%dHCaO~nwOrm5E54=aDg(&HR4S23Oa#-a^=}w%g?ZP-1iq8PSjE8jYaGZu z$I)?YN8he?F9>)2d$G6a*zm0XB*Rf&gZAjq(8l@CUDSY1tB#!i> zW$VfG%#SYSiZ};)>pHA`qlfDTEYQEwN6>NNEp+uxuqx({Fgr zjI@!4xRc?vk^9+~eU|mzH__dCDI=xb{Cd}4bELS9xRaS!*FXMwtMR-RR%SLMh0Cjl zencr8#Su<4(%}$yGVBU-HX{18v=yPH*+%^Vtknc>2A;%-~DrYFx^3XfuVgvZ{#1tA== zm3>IzAM2{3Iv_d1XG{P6^tN3|PkJMnjs&CWN7%7_CmjoVakUhsa&dMv==2~^ri?&x zVdv*rnfVyM+I1^Kg*S=23mR@+0T9BWFZUu~@toA8d)fw6be=`Yb6DSX6D?jB%2YT~ z*aHjtIOozfMhA!Jd*?u5_n!SnX>vX`=Ti-1HA4RiE>eI3vTn zz+>Ccf0HX6Ans-ebOB>RJST-Cyr#4XAk+mAlJgdQnoE{^iIN)OcYFSpgJUmXtl@tT z-^ZuUeSj5hSFrQwqX>~EtZ*{>Gi8Bu9_|o06oNtaXP?E936!a@DsvS*tsB@fa6kEA z5GkjwmH?EgpiG&itsB_Tb1NxtFnvxh_s@9KYX1Sttf?AlI~)z zT=6Y7ulx=}<8Scr_UqU-_z)5gPo%050PsbM*ZLno;_-ow&k?FZJtYmb2hPA$LkP)8 z=^d0Q6PImh6Y|QT?{grxj)S=uBKvY2EQUbm@ns9^yKiP~$DcD)c$5Em`zDSScH%iH zVov&m=cMo`1tYwA=!a}vb_ef_{)Q2?FUqn>BR$6phXQRv^1%=YfyE-F$AR4Q?9D!f zCzB^^#td~4u&l~l#rp2QLfe3+_ub9@+|x+m;=2(sQ`s%gO|j$XBb>A7Q(UydipiMw%igcweV#Cr~SP);q>w`bxts_4} znKHg?X==JDkQl3Y>Ckt%`s{n?Nq-1Fw5~%Mq$CAsi-`yu_bKm zxs#QdE7&vgJD%M84f4SNzSDv)S|V?|$!d5a#lhT5>>YWE4NGqa9-fbmV$=)@k&32kdEYetna>=j@0>V8+wRsL;po!3ivVwh<9tn z2S<1u9DAAQ>x1Sn=fk`)At|quvleV($B|#Kap_lB-F^*yV=wZ{9baUu(uXfokr95^ zA*!*W=5a>$2Ps`-F^+qRQT^{*cN>vipT*4!r#p%{(#I7s z0NN94*q?ib$KJjfDI_sjHNdmEVp5wB&j54O#VoFqBwy)gfA$%)4d_X4q${L9Xom2R3xy&ZBSNgt4a1d7K^CDWa9r zVb-_52m}Vp)`9;ZSKd#|U4ZYj5}Gp49{4utST|=c`~(#>KHF6}CCov1iHYw zt{bWo)A@yF2$~c(nR$rSAaFQ$(Wh{vkG1AlutDMw=mM`C`T=X&|Ad9fb5Od}ROt1z zOpczHqrb4Jo^rSCiW#&o(m7jFamnrsTpQb;*h4o8r#$aZ}2RaT-x2u^^ z%u@YyIv$U^u~@9(XGbSwU@fk6SikH>j+D1jQrYTKGJpW%vUT{!d}7THI5&Sa?~MKy zS0-mvMl+BOcroEJ@hN!2H_?coTEJ5Q<;Nd?yx;eIj4{$$E2?YUO|NtNPJ-PdDf;s} zab;}Mz0kbOI}5*w@3gROcnl#5)wQnEhDBfn!Xhy`u>C}*E~vWpO^HS)FC>8^umI=+ z&H;LW6w#;EF`}vQd_9Muru`KnQVPI9U?(sD)&Dg-0j3#(!fNKVZ_GoYH{la~d*1Yh$TI-TL>mI4vpNb@sU2=IZ8vL%AXUx0 zz{K0|nK(yizLHaeW#ZhRfQXoK^}1$=$#1{Yn002ovPDHLkV1n#w+^+xt literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926
r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY diff --git a/androidgcs/res/drawable-ldpi/icon.png b/androidgcs/res/drawable-ldpi/icon.png index eab1fc68fd7ad531ac025a53956f78de8d4e5180..1095584ec21f71cd0afc9e0993aa2209671b590c 100644 GIT binary patch literal 1723 zcmV;s21NOZP)AReP91Tc8>~sHP8V>Ys(CF=aT`Sk=;|pS}XrJPb~T1dys{sdO&0YpQBSz*~us zcN*3-J_EnE1cxrXiq*F~jZje~rkAe3vf3>;eR)3?Ox=jK*jEU7Do|T`2NqP{56w(* zBAf)rvPB_7rsfeKd0^!CaR%BHUC$tsP9m8a!i@4&TxxzagzsYHJvblx4rRUu#0Jlz zclZJwdC}7S3BvwaIMTiwb!98zRf|zoya>NudJkDGgEYs=q*HmC)>GExofw=92}s;l z_YgKLUT5`<1RBwq{f)K~I%M=gRE6d)b5BP`8{u9x0-wsG%H)w^ zRU7n9FwtlfsZSjiSB(k8~Y5+O>dyoSI477Ly?|FR?m))C!ci%BtY!2Sst8Uri#|SFX&)8{_Ou2 z9r5p3Vz9_GY#%D>%huqp_>U}K45YGy__TE!HZA@bMxX~@{;>cGYRgH~Ih*vd7EgV7h6Pg$#$lH+5=^lj{W80p{{l+;{7_t5cv3xVUy zl_BY4ht1JH*EEeRS{VwTC(QFIVu8zF&P8O$gJsMgsSO35SVvBrX`Vah$Yz2-5T>-`4DJNH;N zlSSY8-mfty+|1~*;BtTwLz_w5 z+lRv)J28~G%ouyvca(@|{2->WsPii&79&nju7ITE6hMX4AQc{|KqZN#)aAvemg3IZ zCr}Y+!r}JU&^>U1C2WyZC<=47itSYQ`?$5{VH?mtFMFFExfYTsfqK%*WzH@Onc#i` zI@a|rm-WbKk{5my{mF}H>Duc$bit&yLAgFfqo2vVbm~?FeG#0F?dSP*kxSo0Ff!o@ z(C}B;r&6pa-NY4;y~5lX8g&*MYQ>yLGd^tDWC4(sGy$Ow-*!eh%xt;>ve|J1q$*w< zh;B#cz!6l2=5bkX#nJ9PJQ`ew8t>7z$bxqf*QB=l2_UB$hK|1EIfloN-jQ=qcwChF zYAkkyp=;FwcnUB3v0=*tMYMA(HdyvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY diff --git a/androidgcs/res/drawable-mdpi/icon.png b/androidgcs/res/drawable-mdpi/icon.png index eab1fc68fd7ad531ac025a53956f78de8d4e5180..a07c69fa5a0f4da5d5efe96eea12a543154dbab6 100644 GIT binary patch literal 2574 zcmV+p3i0)cP)Q`Og{P|8RRXpj5bgrSmEzSMfBn+{{vpNxw?;5UX;iv9sYxy_`IQHs$i<61a_iv^L>h8s-`D(`e@|IgS*Fj zNGM876Gf;3D8*1UX9a%v>yJKD*QkCwW2AirU(L{qNA)JghmGItc;(H<$!ABY&gBy1vJIEUj-b8%el*o|VkG)LqNx#TG>Jvj^jIte!!+RY z)T4j$7+PoF1AkRBf}R#^T=-q|PaK1$c<4UH)Hpq3$4WA|xtr!ZQLC=*vNE>O6E9kp+5X0eKB$6>C(lPwI@3#oY zhS_%x7e|j!$yG?ECXmh~EH~^OeuK}+sWoJse3Z3?ha3n`MM9KvA?uqpEnBg4Q46)7 zM$p%a$@l;+O}vfvx%XjH`}a{(-HHth9!JaUwV0*VqGR48^gWNYN<&~7x)y$e!X>e` zZ5!6KZoxbKuV9XUDI%#M1~IVh?pNSdeb~6@$y`v|yk=XK+fHxnDqnUK4&=QRNyIVf zYbDM*cI>~qIy*a7=z7uqkw@agd(<=y-Q7L!ty_23SGdXmahO<;N=wB+j;lNm%=OHC zy zU|>La6h%92y4IPufI$9>Xu!@y`TaNgtg&41@PwMwBdmSm7)xAWDLoqjZ==P2#*k7! z3o1)cVSI3KP_!?d8G^Lg0FtLXC~JYdxi|c%h~lXEixY=%VSFF@!*3&&9>(Rb|iK54Cx5;s~PY5iaV1het%w`dgQFBAJ;aFK zImQC}(|QaCFYUm1JVfzSc)ebv=)ObI)0jwJb``}Zj9J0n0Xgn*Zc(rFM9$xh_makZbm-at_v5^SW zM1y1SW@%+FuIy*WR)i3A2N_q;(YO`O!A|Ts^%z}9ZepCj3ytlw#x%N_fNrKKtPh`< z|1{UqF`4LxHaCQ79+E=uUXCOZ35jAMRz%R%0(P!0FMv=sk>Nr8%+OzY^c-M9@+fz=G`qa@v4sF5u-2289-#$**LWnyNNDwDf1( zkUiMnw|y$tn>pQP=Vn!#|17L^5AGrjtBkN$D@v)Z7LXc5EFhLB4<;7Wehh)CMqX|W zqsiZaO^benJ_hwa&V0ub$-_HUk**?g6fm9|!@kguU6*zhK)$qn-<3*kFrYPIaqR=V zUaUvk>@F_89b@tHs8R!*QKY;INJ<2_U+K6Ca3e9Gsl2{qY0%a7J?uICWgHuLfj+MB z=GkAN1&ifT#2u}B+2S#~$5jA(Qn^;H%CCmIae4AE-Dsng|Hl*Ov!z72k3ZnJs{pp| z+pW`DDueC#mEWOf=ucJ!dTL}hzOeiS-i?m2E;`EKz4<&Lu~NnW?peqVU^@<+T3KKu z{yrI%Qy-Z%HEvLUz}n^~m?7x`xuCtNR#L2En!T>dQtIKdS#V-Hzt3RtwTeYtmQ&dR z6qXZvac*oc@BUYEH%@Ylv_1&tSjkbzzU6*h1(3^C`;1z;g_SmOtclS?KWk2VYE zM*oS<=C483XckW?GN|1jfh3Ro(hvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY diff --git a/androidgcs/res/layout/objectbrowser.xml b/androidgcs/res/layout/objectbrowser.xml deleted file mode 100644 index 02a3f5dd6..000000000 --- a/androidgcs/res/layout/objectbrowser.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index eba6becf8..0d9f93bc2 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,7 +1,5 @@ - OpenPilot Android GCS - OpieMobi - #FFFFFF - #000000 + Hello World! + OpenPilot GCS diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java b/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java deleted file mode 100644 index 190668d80..000000000 --- a/androidgcs/src/org/openpilot/androidgcs/ObjBrowserExpandableListAdapter.java +++ /dev/null @@ -1,99 +0,0 @@ -/** - * - */ -package org.openpilot.androidgcs; - -import android.widget.AbsListView; -import android.widget.TextView; -import android.content.Context; -import android.view.Gravity; -import android.view.View; -import android.view.ViewGroup; -import android.widget.BaseExpandableListAdapter; - -/** - * @author jcotton81 - * - */ -public class ObjBrowserExpandableListAdapter extends BaseExpandableListAdapter { - - // Sample data set. children[i] contains the children (String[]) for - // groups[i]. - private String[] groups = { "Parent1", "Parent2", "Parent3" }; - private String[][] children = { { "Child1" },{ "Child2" }, { "Child3" },{ "Child4" }, { "Child5" } }; - - private Context context; - - public ObjBrowserExpandableListAdapter(Context context) { - this.context = context; - } - - public Object getChild(int groupPosition, int childPosition) { - return children[groupPosition][childPosition]; - } - - public long getChildId(int groupPosition, int childPosition) { - return childPosition; - } - - public int getChildrenCount(int groupPosition) { - int i = 0; - try { - i = children[groupPosition].length; - - } catch (Exception e) { - } - - return i; - } - - public TextView getGenericView() { - // Layout parameters for the ExpandableListView - AbsListView.LayoutParams lp = new AbsListView.LayoutParams( - ViewGroup.LayoutParams.FILL_PARENT, 64); - - TextView textView = new TextView(context); - textView.setLayoutParams(lp); - // Center the text vertically - textView.setGravity(Gravity.CENTER_VERTICAL | Gravity.LEFT); - // Set the text starting position - textView.setPadding(36, 0, 0, 0); - return textView; - } - - public View getChildView(int groupPosition, int childPosition, - boolean isLastChild, View convertView, ViewGroup parent) { - TextView textView = getGenericView(); - textView.setText(getChild(groupPosition, childPosition).toString()); - return textView; - } - - public Object getGroup(int groupPosition) { - return groups[groupPosition]; - } - - public int getGroupCount() { - return groups.length; - } - - public long getGroupId(int groupPosition) { - return groupPosition; - } - - public View getGroupView(int groupPosition, boolean isExpanded, - View convertView, ViewGroup parent) { - TextView textView = getGenericView(); - textView.setText(getGroup(groupPosition).toString()); - return textView; - } - - public boolean isChildSelectable(int groupPosition, int childPosition) { - return true; - } - - public boolean hasStableIds() { - return true; - } - - -} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java deleted file mode 100644 index 19e9b2812..000000000 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ /dev/null @@ -1,21 +0,0 @@ -package org.openpilot.androidgcs; - -import android.app.Activity; -import android.os.Bundle; - -import android.widget.*; - -public class ObjectBrowser extends Activity { - /** Called when the activity is first created. */ - @Override - public void onCreate(Bundle savedInstanceState) { - super.onCreate(savedInstanceState); - - setContentView(R.layout.objectbrowser); - ExpandableListAdapter mAdapter; - ExpandableListView epView = (ExpandableListView) findViewById(R.id.objects); - mAdapter = new ObjBrowserExpandableListAdapter(this); - epView.setAdapter(mAdapter); - - } -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index a1e5773b9..e5197b02e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -2,13 +2,11 @@ package org.openpilot.uavtalk; public class UAVMetaObject extends UAVObject { - public UAVMetaObject(int objID, Boolean isSingleInst, String name) { - super(objID, isSingleInst, name); - // TODO Auto-generated constructor stub - } - - public UAVMetaObject(int objID, String mname, UAVDataObject obj) { - // TODO Auto-generated constructor stub + private UAVDataObject parent; + + public UAVMetaObject(int objID, String mname, UAVDataObject parent) { + super(objID, true, mname); + this.parent = parent; } @Override From 1810fb61a0dd1549be60621471f08111cc89bdc8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 1 Mar 2011 22:27:58 -0600 Subject: [PATCH 195/543] Update the object template to be more consistent with ground code --- .../templates/uavobjecttemplate.java | 23 ++++++++++--------- 1 file changed, 12 insertions(+), 11 deletions(-) diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index 285ad03aa..13eeeb724 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -29,30 +29,31 @@ package org.openpilot.uavtalk.uavobjects; import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVObjectMetaData; -import org.openpilot.uavtalk.UAVObjectFieldDescription; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVMetaObject; + /** $(DESCRIPTION) generated from $(XMLFILE) **/ -public class $(NAME) extends UAVObject{ +public class $(NAME) extends UAVDataObject{ $(FIELDSINIT) public void setGeneratedMetaData() { - getMetaData().gcsAccess = UAVObjectMetaData.$(GCSACCESS); - getMetaData().gcsTelemetryAcked = UAVObjectMetaData.$(GCSTELEM_ACKEDTF); - getMetaData().gcsTelemetryUpdateMode = UAVObjectMetaData.$(GCSTELEM_UPDATEMODE); + getMetaData().gcsAccess = UAVMetaObject.$(GCSACCESS); + getMetaData().gcsTelemetryAcked = UAVMetaObject.$(GCSTELEM_ACKEDTF); + getMetaData().gcsTelemetryUpdateMode = UAVMetaObject.$(GCSTELEM_UPDATEMODE); getMetaData().gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - getMetaData().flightAccess = UAVObjectMetaData.$(FLIGHTACCESS); - getMetaData().flightTelemetryAcked = UAVObjectMetaData.$(FLIGHTTELEM_ACKEDTF); - getMetaData().flightTelemetryUpdateMode = UAVObjectMetaData.$(FLIGHTTELEM_UPDATEMODE); + getMetaData().flightAccess = UAVMetaObject.$(FLIGHTACCESS); + getMetaData().flightTelemetryAcked = UAVMetaObject.$(FLIGHTTELEM_ACKEDTF); + getMetaData().flightTelemetryUpdateMode = UAVMetaObject.$(FLIGHTTELEM_UPDATEMODE); getMetaData().flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - getMetaData().loggingUpdateMode = UAVObjectMetaData.$(LOGGING_UPDATEMODE); + getMetaData().loggingUpdateMode = UAVMetaObject.$(LOGGING_UPDATEMODE); getMetaData().loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); } @@ -65,7 +66,7 @@ $(FIELDSINIT) return "$(NAME)"; } - public String getObjDescription() { + public String getDescription() { return "$(DESCRIPTION)"; } From f0e4c10cfae12a45b6d30657f01b43a36fd60a54 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 2 Mar 2011 20:23:27 -0600 Subject: [PATCH 196/543] Continuing to work on the java code to be more consistent with GCS code --- androidgcs/.classpath | 1 + .../org/openpilot/uavtalk/UAVDataObject.java | 34 +++++++++++--- .../org/openpilot/uavtalk/UAVMetaObject.java | 47 +++++++++++++++---- .../src/org/openpilot/uavtalk/UAVObject.java | 36 ++++++++++---- .../templates/uavobjecttemplate.java | 30 ++++++++---- 5 files changed, 117 insertions(+), 31 deletions(-) diff --git a/androidgcs/.classpath b/androidgcs/.classpath index 609aa00eb..b24a2abf5 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -3,5 +3,6 @@ + diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index 12a4263c0..a2e6acf9e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -2,17 +2,20 @@ package org.openpilot.uavtalk; public abstract class UAVDataObject extends UAVObject { + /** + * @brief Constructor for UAVDataObject + * @param objID the object id to be created + * @param isSingleInst + * @param isSet + * @param name + */ public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) { super(objID, isSingleInst, name); } - public void initialize(int instID, UAVMetaObject mobj) { - - } + public abstract void initialize(int instID, UAVMetaObject mobj); - public void initialize(UAVMetaObject mobj) { - - } + public abstract void initialize(UAVMetaObject mobj); Boolean isSettings() { return null; @@ -22,6 +25,23 @@ public abstract class UAVDataObject extends UAVObject { return null; } - public abstract UAVDataObject clone(int instID); + public UAVDataObject clone(int instID) { + try { + return (UAVDataObject) super.clone(); + } catch (CloneNotSupportedException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + return null; + } + +public: + static int OBJID = $(OBJIDHEX); + static String NAME; + static String DESCRIPTION; + static boolean ISSINGLEINST = $(ISSINGLEINST); + static boolean ISSETTINGS = $(ISSETTINGS); + static int NUMBYTES = sizeof(DataFields); + } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index e5197b02e..9c2e3b12d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -2,23 +2,41 @@ package org.openpilot.uavtalk; public class UAVMetaObject extends UAVObject { - private UAVDataObject parent; - - public UAVMetaObject(int objID, String mname, UAVDataObject parent) { - super(objID, true, mname); + public UAVMetaObject(int objID, String name, UAVDataObject parent) { + super(objID, true, name); this.parent = parent; + + ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + ownMetadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + ownMetadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.flightTelemetryUpdatePeriod = 0; + ownMetadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + ownMetadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.gcsTelemetryUpdatePeriod = 0; + ownMetadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.loggingUpdatePeriod = 0; + + } + + UAVObject getParentObject() { + return parent; } @Override public void deserialize(byte[] arr, int offset) { // TODO Auto-generated method stub - + } @Override - public UAVMetaObject getDefaultMetadata() { - // TODO Auto-generated method stub - return null; + public Metadata getMetadata() { + return ownMetadata; + } + + @Override + public Metadata getDefaultMetadata() { + return ownMetadata; } @Override @@ -45,4 +63,17 @@ public class UAVMetaObject extends UAVObject { return null; } + + public UAVMetaObject(quint32 objID, const QString& name, UAVObject* parent); + UAVObject* getParentObject(); + void setMetadata(const Metadata& mdata); + void setData(const Metadata& mdata); + Metadata getData(); + + + private UAVObject parent; + private Metadata ownMetadata; + private Metadata parentMetadata; + + } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index c5ffc9d21..1decf3563 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -20,11 +20,27 @@ public abstract class UAVObject { ACCESS_READWRITE, ACCESS_READONLY } ; - - - private Boolean isSingleInst; - private int instID; - private UAVMetaObject meta; + + /** + * Access mode + */ + public enum Acked{ + FALSE, + TRUE + } ; + + final class Metadata { + public AccessMode flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ + public AccessMode gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ + public Acked flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ + public UpdateMode flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ + public int flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ + public Acked gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ + public UpdateMode gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ + public int gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + public UpdateMode loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ + public int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ + } ; public UAVObject(int objID, Boolean isSingleInst, String name) { assert(objID == getObjID()); // ID is in implementation code, make sure it matches object @@ -62,9 +78,13 @@ public abstract class UAVObject { return true; } - public void setMetadata(UAVMetaObject obj) { meta = obj; } - public UAVMetaObject getMetadata() { return meta; } - public abstract UAVMetaObject getDefaultMetadata(); + public abstract void setMetadata(Metadata obj); + public abstract Metadata getMetadata(); + public abstract Metadata getDefaultMetadata(); + + private Boolean isSingleInst; + private int instID; + private UAVMetaObject meta; /* // Unported code from QT diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index 13eeeb724..fa09f782f 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -31,29 +31,34 @@ package org.openpilot.uavtalk.uavobjects; import org.openpilot.uavtalk.UAVObject; import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVMetaObject; +import org.openpilot.uavtalk.UAVObjectField; /** $(DESCRIPTION) generated from $(XMLFILE) **/ -public class $(NAME) extends UAVDataObject{ +public class $(NAME) extends UAVDataObject { $(FIELDSINIT) + public $(NAME) (int objID, Boolean isSingleInst, Boolean isSet, String name) { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + } + public void setGeneratedMetaData() { - getMetaData().gcsAccess = UAVMetaObject.$(GCSACCESS); - getMetaData().gcsTelemetryAcked = UAVMetaObject.$(GCSTELEM_ACKEDTF); - getMetaData().gcsTelemetryUpdateMode = UAVMetaObject.$(GCSTELEM_UPDATEMODE); + getMetaData().gcsAccess = UAVObject.AccessMode.$(GCSACCESS); + getMetaData().gcsTelemetryAcked = UAVObject.Acked.$(GCSTELEM_ACKEDTF); + getMetaData().gcsTelemetryUpdateMode = UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE); getMetaData().gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - getMetaData().flightAccess = UAVMetaObject.$(FLIGHTACCESS); - getMetaData().flightTelemetryAcked = UAVMetaObject.$(FLIGHTTELEM_ACKEDTF); - getMetaData().flightTelemetryUpdateMode = UAVMetaObject.$(FLIGHTTELEM_UPDATEMODE); + getMetaData().flightAccess = UAVObject.AccessMode.$(FLIGHTACCESS); + getMetaData().flightTelemetryAcked = UAVObject.Acked.$(FLIGHTTELEM_ACKEDTF); + getMetaData().flightTelemetryUpdateMode = UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE); getMetaData().flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - getMetaData().loggingUpdateMode = UAVMetaObject.$(LOGGING_UPDATEMODE); + getMetaData().loggingUpdateMode = UAVObject.UpdateMode.$(LOGGING_UPDATEMODE); getMetaData().loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); } @@ -69,6 +74,15 @@ $(FIELDSINIT) public String getDescription() { return "$(DESCRIPTION)"; } +protected: + // Constants + static final int OBJID = $(OBJIDHEX); + static final String NAME; + static final String DESCRIPTION; + static final boolean ISSINGLEINST = $(ISSINGLEINST); + static final boolean ISSETTINGS = $(ISSETTINGS); + static final int NUMBYTES = sizeof(DataFields); + $(GETTERSETTER) } \ No newline at end of file From c3244cf5a231e302c6ccd59cfd0d306bbb584aeb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 4 Mar 2011 00:06:17 -0600 Subject: [PATCH 197/543] Import of UAVObjectField object. This differs a bit from the GCS implementation in that the data is stored within the field instead of being packed back into a continugious memory region. This is because java doesn't allow casting to struct so the memory access isn't a useful feature. --- .../org/openpilot/uavtalk/UAVObjectField.java | 468 ++++++++++++++++++ 1 file changed, 468 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java new file mode 100644 index 000000000..832e7048a --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -0,0 +1,468 @@ +package org.openpilot.uavtalk; + +import java.io.Serializable; +import java.nio.ByteBuffer; +import java.nio.ByteOrder; +import java.util.ArrayList; +import java.util.List; + +public class UAVObjectField { + + public enum FieldType { INT8, INT16, INT32, UINT8, UINT16, UINT32, FLOAT32, ENUM, STRING }; + + public UAVObjectField(String name, String units, FieldType type, int numElements, List options) { + List elementNames = new ArrayList(); + // Set element names + for (int n = 0; n < numElements; ++n) + { + elementNames.add(String.valueOf(n)); + } + // Initialize + constructorInitialize(name, units, type, elementNames, options); + } + + public UAVObjectField(String name, String units, FieldType type, List elementNames, List options) { + constructorInitialize(name, units, type, elementNames, options); + } + + public void initialize(byte[] data, int dataOffset, UAVObject obj){ + this.data = data; + this.offset = dataOffset; + this.obj = obj; + clear(); + + } + + public UAVObject getObject() { + return obj; + } + + public FieldType getType() { + return type; + } + + public String getTypeAsString() { + switch (type) + { + case INT8: + return "int8"; + case INT16: + return "int16"; + case INT32: + return "int32"; + case UINT8: + return "uint8"; + case UINT16: + return "uint16"; + case UINT32: + return "uint32"; + case FLOAT32: + return "float32"; + case ENUM: + return "enum"; + case STRING: + return "string"; + default: + return ""; + } + } + + public String getName() { + return name; + } + + public String getUnits() { + return units; + } + + public int getNumElements() { + return numElements; + } + + public List getElementNames() { + return elementNames; + } + + public List getOptions() { + return options; + } + + /** + * This function copies this field from the internal storage of the parent object + * to a new ByteBuffer for UAVTalk. It also converts from the java standard (big endian) + * to the arm/uavtalk standard (little endian) + * @param dataOut + * @return +] + * @throws Exception */ + public int pack(ByteBuffer dataOut) throws Exception { + //QMutexLocker locker(obj->getMutex()); + // Pack each element in output buffer + dataOut.order(ByteOrder.LITTLE_ENDIAN); + switch (type) + { + case INT8: + for (int index = 0; index < numElements; ++index) + dataOut.put((Byte) getValue(index)); + break; + case INT16: + for (int index = 0; index < numElements; ++index) + dataOut.putShort((Short) getValue(index)); + break; + case INT32: + for (int index = 0; index < numElements; ++index) + dataOut.putInt((Integer) getValue(index)); + break; + case UINT8: + // TODO: Deal properly with unsigned + for (int index = 0; index < numElements; ++index) + dataOut.put((Byte) getValue(index)); + break; + case UINT16: + // TODO: Deal properly with unsigned + for (int index = 0; index < numElements; ++index) + dataOut.putShort((Short) getValue(index)); + break; + case UINT32: + // TODO: Deal properly with unsigned + for (int index = 0; index < numElements; ++index) + dataOut.putInt((Integer) getValue(index)); + break; + case FLOAT32: + for (int index = 0; index < numElements; ++index) + dataOut.putFloat((Float) getValue(index)); + break; + case ENUM: + List l = (List) data; + for (int index = 0; index < numElements; ++index) + dataOut.put((Byte) l.get(index)); + break; + case STRING: + // TODO: Implement strings + throw new Exception("Strings not yet implemented"); + } + // Done + return getNumBytes(); + } + + public int unpack(ByteBuffer dataIn) throws Exception { + // Unpack each element from input buffer + dataIn.order(ByteOrder.LITTLE_ENDIAN); + switch (type) + { + case INT8: + for (int index = 0 ; index < numElements; ++index) { + setValue((Byte) dataIn.get(), index); + } + break; + case INT16: + for (int index = 0 ; index < numElements; ++index) { + setValue((Short) dataIn.getShort(), index); + } + break; + case INT32: + for (int index = 0 ; index < numElements; ++index) { + setValue((Integer) dataIn.getInt(), index); + } + break; + case UINT8: + // TODO: Deal with unsigned + for (int index = 0 ; index < numElements; ++index) { + setValue((Byte) dataIn.get(), index); + } + break; + case UINT16: + // TODO: Deal with unsigned + for (int index = 0 ; index < numElements; ++index) { + setValue((Short) dataIn.getShort(), index); + } + break; + case UINT32: + // TODO: Deal with unsigned + for (int index = 0 ; index < numElements; ++index) { + setValue((Integer) dataIn.getInt(), index); + } + break; + case FLOAT32: + for (int index = 0 ; index < numElements; ++index) { + setValue((Float) dataIn.getFloat(), index); + } + break; + case ENUM: + List l = (List) data; + for (int index = 0 ; index < numElements; ++index) { + l.set(index, dataIn.get(index)); + } + break; + case STRING: + throw new Exception("Strings not handled"); + } + // Done + return getNumBytes(); + } + + Object getValue() throws Exception { return getValue(0); }; + Object getValue(int index) throws Exception { +// QMutexLocker locker(obj->getMutex()); + // Check that index is not out of bounds + if ( index >= numElements ) + { + return null; + } + + switch (type) + { + case INT8: + case INT16: + case INT32: + { + List l = (List) data; + return l.get(index); + } + case UINT8: + case UINT16: + case UINT32: + { + // TODO: Correctly deal with unsigned values + List l = (List) data; + return l.get(index); + } + case FLOAT32: + { + List l = (List) data; + return l.get(index); + } + case ENUM: + { + List l = (List) data; + Byte val = l.get(index); + + if(val >= options.size() || val < 0) + throw new Exception("Invalid value for" + name); + + return options.get(val); + } + case STRING: + { + throw new Exception("Shit I should do this"); + } + } + // If this point is reached then we got an invalid type + return null; + } + + public void setValue(Object data) throws Exception { setValue(data,0); } + public void setValue(Object data, int index) throws Exception { + // QMutexLocker locker(obj->getMutex()); + // Check that index is not out of bounds + if ( index >= numElements ) + throw new Exception("Index out of bounds"); + + // Get metadata + UAVObject.Metadata mdata = obj.getMetadata(); + // Update value if the access mode permits + if ( mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) + { + ByteBuffer bbuf = ByteBuffer.allocate(numBytesPerElement); + switch (type) + { + case INT8: + case INT16: + case INT32: + { + List l = (List) data; + l.set(index, (Integer) data); + break; + } + case UINT8: + case UINT16: + case UINT32: + { + List l = (List) data; + l.set(index, (Integer) data); + break; + } + case FLOAT32: + { + List l = (List) data; + l.set(index, (Float) data); + break; + } + case ENUM: + { + byte val = (byte) options.indexOf((String) data); + if(val < 0) throw new Exception("Enumerated value not found"); + List l = (List) data; + l.set(index, val); + break; + } + case STRING: + { + throw new Exception("Sorry I haven't implemented strings yet"); + } + } + } + } + + public double getDouble() throws Exception { return getDouble(0); }; + public double getDouble(int index) throws Exception { + return Double.valueOf((Double) getValue(index)); + } + + void setDouble(double value) throws Exception { setDouble(value, 0); }; + void setDouble(double value, int index) throws Exception { + setValue(value, index); + } + + int getDataOffset() { + return offset; + } + + int getNumBytes() { + return numBytesPerElement * numElements; + } + + int getNumBytesElement() { + return numBytesPerElement; + } + + boolean isNumeric() { + switch (type) + { + case INT8: + return true; + case INT16: + return true; + case INT32: + return true; + case UINT8: + return true; + case UINT16: + return true; + case UINT32: + return true; + case FLOAT32: + return true; + case ENUM: + return false; + case STRING: + return false; + default: + return false; + } + } + + boolean isText() { + switch (type) + { + case INT8: + return false; + case INT16: + return false; + case INT32: + return false; + case UINT8: + return false; + case UINT16: + return false; + case UINT32: + return false; + case FLOAT32: + return false; + case ENUM: + return true; + case STRING: + return true; + default: + return false; + } + } + + public String toString() { + String sout = new String(); + sout += name + ": [ "; + for (int n = 0; n < numElements; ++n) + { + sout += String.valueOf(n) + " "; + } + + sout += "] " + units + "\n"; + return sout; + } + + void fieldUpdated(UAVObjectField field) { + + } + + public void clear() { + // TODO: This accesses a shared array of the parent + } + + public void constructorInitialize(String name, String units, FieldType type, List elementNames, List options) { + // Copy params + this.name = name; + this.units = units; + this.type = type; + this.options = options; + this.numElements = elementNames.size(); + this.offset = 0; + this.data = null; + this.obj = null; + this.elementNames = elementNames; + // Set field size + switch (type) + { + case INT8: + data = (Object) new ArrayList(); + numBytesPerElement = 1; + break; + case INT16: + data = (Object) new ArrayList(); + numBytesPerElement = 2; + break; + case INT32: + data = (Object) new ArrayList(); + numBytesPerElement = 4; + break; + case UINT8: + data = (Object) new ArrayList(); + numBytesPerElement = 1; + break; + case UINT16: + data = (Object) new ArrayList(); + numBytesPerElement = 2; + break; + case UINT32: + data = (Object) new ArrayList(); + numBytesPerElement = 4; + break; + case FLOAT32: + data = (Object) new ArrayList(); + numBytesPerElement = 4; + break; + case ENUM: + data = (Object) new ArrayList(); + numBytesPerElement = 1; + break; + case STRING: + data = (Object) new ArrayList(); + numBytesPerElement = 1; + break; + default: + numBytesPerElement = 0; + } + } + + + private String name; + private String units; + private FieldType type; + private List elementNames; + private List options; + private int numElements; + private int numBytesPerElement; + private int offset; + private Object data; + private UAVObject obj; + +} From cd8fac766cb8a2e1b041209d6ceb9e3c53fef7ec Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 4 Mar 2011 10:22:11 -0600 Subject: [PATCH 198/543] Some changes to the object field to get it to initialze the array to be the right length --- .../src/org/openpilot/uavtalk/UAVObject.java | 2 +- .../org/openpilot/uavtalk/UAVObjectField.java | 75 ++++++++++++++----- 2 files changed, 56 insertions(+), 21 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 1decf3563..aaf32151f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -84,7 +84,7 @@ public abstract class UAVObject { private Boolean isSingleInst; private int instID; - private UAVMetaObject meta; + private Metadata meta; /* // Unported code from QT diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 832e7048a..d09008cbe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -25,10 +25,8 @@ public class UAVObjectField { constructorInitialize(name, units, type, elementNames, options); } - public void initialize(byte[] data, int dataOffset, UAVObject obj){ - this.data = data; - this.offset = dataOffset; - this.obj = obj; + public void initialize(UAVObject obj){ + this.obj = obj; clear(); } @@ -258,10 +256,13 @@ public class UAVObjectField { if ( index >= numElements ) throw new Exception("Index out of bounds"); + System.out.println(data.toString()); + System.out.println(this.data.toString()); + // Get metadata - UAVObject.Metadata mdata = obj.getMetadata(); + //UAVObject.Metadata mdata = obj.getMetadata(); // Update value if the access mode permits - if ( mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) + if ( true ) //mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) { ByteBuffer bbuf = ByteBuffer.allocate(numBytesPerElement); switch (type) @@ -270,7 +271,7 @@ public class UAVObjectField { case INT16: case INT32: { - List l = (List) data; + List l = (List) this.data; l.set(index, (Integer) data); break; } @@ -278,13 +279,13 @@ public class UAVObjectField { case UINT16: case UINT32: { - List l = (List) data; + List l = (List) this.data; l.set(index, (Integer) data); break; } case FLOAT32: { - List l = (List) data; + List l = (List) this.data; l.set(index, (Float) data); break; } @@ -292,7 +293,7 @@ public class UAVObjectField { { byte val = (byte) options.indexOf((String) data); if(val < 0) throw new Exception("Enumerated value not found"); - List l = (List) data; + List l = (List) this.data; l.set(index, val); break; } @@ -395,7 +396,37 @@ public class UAVObjectField { } public void clear() { - // TODO: This accesses a shared array of the parent + switch (type) + { + case INT8: + case INT16: + case INT32: + case UINT8: + case UINT16: + case UINT32: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add(0); + } + break; + case FLOAT32: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((float) 0); + } + break; + case ENUM: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((byte)0); + } + break; + case STRING: + // TODO: Add string + break; + default: + numBytesPerElement = 0; + } } public void constructorInitialize(String name, String units, FieldType type, List elementNames, List options) { @@ -410,47 +441,51 @@ public class UAVObjectField { this.obj = null; this.elementNames = elementNames; // Set field size + System.out.println("Initializing: type " + type + this.numElements); + switch (type) { case INT8: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case INT16: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 2; break; case INT32: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case UINT8: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case UINT16: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 2; break; case UINT32: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case FLOAT32: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case ENUM: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case STRING: - data = (Object) new ArrayList(); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; default: numBytesPerElement = 0; } + clear(); + System.out.println("Initialized: " + this.data.toString()); } From ae43ec3eba7fae289043600213d40b077188d11e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 5 Mar 2011 12:29:48 -0600 Subject: [PATCH 199/543] More updates to UAVObject and Field for android app --- .../src/org/openpilot/uavtalk/UAVObject.java | 598 ++++++++++++++---- .../org/openpilot/uavtalk/UAVObjectField.java | 3 +- 2 files changed, 475 insertions(+), 126 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index aaf32151f..f987a03a9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -1,137 +1,487 @@ package org.openpilot.uavtalk; +import java.nio.ByteBuffer; +import java.util.List; +import java.util.ListIterator; + public abstract class UAVObject { - - - /** - * Object update mode - */ - public enum UpdateMode { - UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ - UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ - UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ - UPDATEMODE_NEVER /** Object is never updated */ - } ; - /** - * Access mode - */ - public enum AccessMode{ - ACCESS_READWRITE, - ACCESS_READONLY - } ; - - /** - * Access mode - */ - public enum Acked{ - FALSE, - TRUE - } ; - - final class Metadata { - public AccessMode flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ - public AccessMode gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ - public Acked flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - public UpdateMode flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ - public int flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ - public Acked gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - public UpdateMode gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ - public int gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ - public UpdateMode loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ - public int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ - } ; - public UAVObject(int objID, Boolean isSingleInst, String name) { - assert(objID == getObjID()); // ID is in implementation code, make sure it matches object - assert(name.equals(getName())); - this.isSingleInst = isSingleInst; - meta = getDefaultMetadata(); - }; - - public void initialize(int instID) { - this.instID = instID; - } - - public int getInstID() { return instID; } - public Boolean isSingleInstance() { return isSingleInst; } - public String getName() { return getObjName(); } // matching QT API to the current autogen code - - public abstract int getObjID(); - public abstract String getDescription(); - public abstract String getObjName(); - - int getNumBytes() { - return serialize().length; - } + /** + * Object update mode + */ + public enum UpdateMode { + UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ + UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ + UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ + UPDATEMODE_NEVER /** Object is never updated */ + } ; - // The name of the serializer and deserialize from the autogenerated code - public abstract byte[] serialize(); - public abstract void deserialize(byte[] arr,int offset); - - byte [] pack() { - return serialize(); - } - - Boolean unpack(byte [] data) { - deserialize(data, 0); - return true; - } - - public abstract void setMetadata(Metadata obj); - public abstract Metadata getMetadata(); - public abstract Metadata getDefaultMetadata(); + /** + * Access mode + */ + public enum AccessMode{ + ACCESS_READWRITE, + ACCESS_READONLY + } ; - private Boolean isSingleInst; - private int instID; - private Metadata meta; + /** + * Access mode + */ + public enum Acked{ + FALSE, + TRUE + } ; - /* - // Unported code from QT - bool save(); - bool save(QFile& file); - bool load(); - bool load(QFile& file); - virtual void setMetadata(const Metadata& mdata) = 0; - virtual Metadata getMetadata() = 0; - virtual Metadata getDefaultMetadata() = 0; - void requestUpdate(); - void updated(); - void lock(); - void lock(int timeoutMs); - void unlock(); - QMutex* getMutex(); - qint32 getNumFields(); - QList getFields(); - UAVObjectField* getField(const QString& name); - QString toString(); - QString toStringBrief(); - QString toStringData(); - void emitTransactionCompleted(bool success); + protected final class Metadata { + public AccessMode flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ + public AccessMode gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ + public Acked flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ + public UpdateMode flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ + public int flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ + public Acked gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ + public UpdateMode gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ + public int gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + public UpdateMode loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ + public int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ + } ; - signals: - void objectUpdated(UAVObject* obj); - void objectUpdatedAuto(UAVObject* obj); - void objectUpdatedManual(UAVObject* obj); - void objectUnpacked(UAVObject* obj); - void updateRequested(UAVObject* obj); - void transactionCompleted(UAVObject* obj, bool success); + public UAVObject(int objID, Boolean isSingleInst, String name) { + this.objID = objID; + this.instID = 0; + this.isSingleInst = isSingleInst; + this.name = name; + // this.mutex = new QMutex(QMutex::Recursive); + }; - private slots: - void fieldUpdated(UAVObjectField* field); + public void initialize(int instID) { + //QMutexLocker locker(mutex); + this.instID = instID; + } - protected: - quint32 objID; - quint32 instID; - bool isSingleInst; - QString name; - QString description; - quint32 numBytes; - QMutex* mutex; - quint8* data; - QList fields; + /** + * Initialize objects' data fields + * @param fields List of fields held by the object + * @param data Pointer to that actual object data, this is needed by the fields to access the data + * @param numBytes Number of bytes in the object (total, including all fields) + * @throws Exception When unable to unpack a field + */ + public void initializeFields(List fields, ByteBuffer data, int numBytes) throws Exception + { + // TODO: QMutexLocker locker(mutex); + this.numBytes = numBytes; + this.data = data; + this.fields = fields; + // Initialize fields + for (int n = 0; n < fields.size(); ++n) + { + fields.get(n).initialize(this); + } + unpack(data); + } - void initializeFields(QList& fields, quint8* data, quint32 numBytes); - void setDescription(const QString& description); - */ + /** + * Get the object ID + */ + public int getObjID() + { + return objID; + } + + /** + * Get the instance ID + */ + public int getInstID() + { + return instID; + } + + /** + * Returns true if this is a single instance object + */ + public boolean isSingleInstance() + { + return isSingleInst; + } + + /** + * Get the name of the object + */ + public String getName() + { + return name; + } + + /** + * Get the description of the object + * @return The description of the object + */ + public String getDescription() + { + return description; + } + + /** + * Set the description of the object + * @param The description of the object + * @return + */ + public void setDescription(String description) + { + this.description = description; + } + + + /** + * Get the total number of bytes of the object's data + */ + public int getNumBytes() + { + return numBytes; + } + + // /** + // * Request that this object is updated with the latest values from the autopilot + // */ + // /* void UAVObject::requestUpdate() + // { + // emit updateRequested(this); + // } */ + // + // /** + // * Signal that the object has been updated + // */ + // /* void UAVObject::updated() + // { + // emit objectUpdatedManual(this); + // emit objectUpdated(this); + // } */ + // + // /** + // * Lock mutex of this object + // */ + // /* void UAVObject::lock() + // { + // mutex->lock(); + // } */ + // + // /** + // * Lock mutex of this object + // */ + // /* void UAVObject::lock(int timeoutMs) + // { + // mutex->tryLock(timeoutMs); + // } */ + // + // /** + // * Unlock mutex of this object + // */ + // /* void UAVObject::unlock() + // { + // mutex->unlock(); + // } */ + // + // /** + // * Get object's mutex + // */ + // QMutex* UAVObject::getMutex() + // { + // return mutex; + // } + + /** + * Get the number of fields held by this object + */ + public int getNumFields() + { + //QMutexLocker locker(mutex); + return fields.size(); + } + + /** + * Get the object's fields + */ + public List getFields() + { + //QMutexLocker locker(mutex); + return fields; + } + + /** + * Get a specific field + * @throws Exception + * @returns The field or NULL if not found + */ + public UAVObjectField getField(String name) throws Exception + { + //QMutexLocker locker(mutex); + // Look for field + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + if(field.getName().equals(name)) + return field; + } + throw new Exception("Field not found"); + } + + /** + * Pack the object data into a byte array + * @param dataOut ByteBuffer to receive the data. + * @throws Exception + * @returns The number of bytes copied + * @note The array must already have enough space allocated for the object + */ + public int pack(ByteBuffer dataOut) throws Exception + { + // QMutexLocker locker(mutex); + if(dataOut.remaining() < getNumBytes()) + throw new Exception("Not enough bytes in ByteBuffer to pack object"); + int numBytes = 0; + + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + numBytes += field.pack(dataOut); + } + return numBytes; + } + + /** + * Unpack the object data from a byte array + * @param dataIn The ByteBuffer to pull data from + * @throws Exception + * @returns The number of bytes copied + */ + public int unpack(ByteBuffer dataIn) throws Exception + { + // QMutexLocker locker(mutex); + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + numBytes += field.unpack(dataIn); + } + return numBytes; + // TODO: Callbacks + //emit objectUnpacked(this); // trigger object updated event + //emit objectUpdated(this); + } + + // /** + // * Save the object data to the file. + // * The file will be created in the current directory + // * and its name will be the same as the object with + // * the .uavobj extension. + // * @returns True on success, false on failure + // */ + // bool UAVObject::save() + // { + // QMutexLocker locker(mutex); + // + // // Open file + // QFile file(name + ".uavobj"); + // if (!file.open(QFile::WriteOnly)) + // { + // return false; + // } + // + // // Write object + // if ( !save(file) ) + // { + // return false; + // } + // + // // Close file + // file.close(); + // return true; + // } + // + // /** + // * Save the object data to the file. + // * The file is expected to be already open for writting. + // * The data will be appended and the file will not be closed. + // * @returns True on success, false on failure + // */ + // bool UAVObject::save(QFile& file) + // { + // QMutexLocker locker(mutex); + // quint8 buffer[numBytes]; + // quint8 tmpId[4]; + // + // // Write the object ID + // qToLittleEndian(objID, tmpId); + // if ( file.write((const char*)tmpId, 4) == -1 ) + // { + // return false; + // } + // + // // Write the instance ID + // if (!isSingleInst) + // { + // qToLittleEndian(instID, tmpId); + // if ( file.write((const char*)tmpId, 2) == -1 ) + // { + // return false; + // } + // } + // + // // Write the data + // pack(buffer); + // if ( file.write((const char*)buffer, numBytes) == -1 ) + // { + // return false; + // } + // + // // Done + // return true; + // } + // + // /** + // * Load the object data from a file. + // * The file will be openned in the current directory + // * and its name will be the same as the object with + // * the .uavobj extension. + // * @returns True on success, false on failure + // */ + // bool UAVObject::load() + // { + // QMutexLocker locker(mutex); + // + // // Open file + // QFile file(name + ".uavobj"); + // if (!file.open(QFile::ReadOnly)) + // { + // return false; + // } + // + // // Load object + // if ( !load(file) ) + // { + // return false; + // } + // + // // Close file + // file.close(); + // return true; + // } + // + // /** + // * Load the object data from file. + // * The file is expected to be already open for reading. + // * The data will be read and the file will not be closed. + // * @returns True on success, false on failure + // */ + // bool UAVObject::load(QFile& file) + // { + // QMutexLocker locker(mutex); + // quint8 buffer[numBytes]; + // quint8 tmpId[4]; + // + // // Read the object ID + // if ( file.read((char*)tmpId, 4) != 4 ) + // { + // return false; + // } + // + // // Check that the IDs match + // if (qFromLittleEndian(tmpId) != objID) + // { + // return false; + // } + // + // // Read the instance ID + // if ( file.read((char*)tmpId, 2) != 2 ) + // { + // return false; + // } + // + // // Check that the IDs match + // if (qFromLittleEndian(tmpId) != instID) + // { + // return false; + // } + // + // // Read and unpack the data + // if ( file.read((char*)buffer, numBytes) != numBytes ) + // { + // return false; + // } + // unpack(buffer); + // + // // Done + // return true; + // } + + /** + * Return a string with the object information + */ + @Override + public String toString() + { + return toStringBrief() + toStringData(); + } + + /** + * Return a string with the object information (only the header) + */ + public String toStringBrief() + { + return String.format("%1 (ID: %2, InstID: %3, NumBytes: %4, SInst: %5)\n", + getName(), + getObjID(), + getInstID(), + getNumBytes(), + isSingleInstance()); + } + + /** + * Return a string with the object information (only the data) + */ + public String toStringData() + { + String s = new String(); + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + s += field.toString(); + } + return s; + } + + // /** + // * Emit the transactionCompleted event (used by the UAVTalk plugin) + // */ + // void UAVObject::emitTransactionCompleted(bool success) + // { + // emit transactionCompleted(this, success); + // } + + /** + * Java specific functions + */ + public UAVObject clone() { + return (UAVObject) clone(); + } + /** + * Abstract functions + */ + public abstract void setMetadata(Metadata mdata); + public abstract Metadata getMetadata(); + public abstract Metadata getDefaultMetadata(); + public abstract UAVDataObject clone(int instID); + protected abstract void setDefaultFieldValues(); + + /** + * Private data for the object, common to all + */ + protected int objID; + protected int instID; + protected boolean isSingleInst; + protected String name; + protected String description; + protected int numBytes; + // TODO: QMutex* mutex; + protected ByteBuffer data; + protected List fields; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index d09008cbe..c7c774199 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -90,8 +90,7 @@ public class UAVObjectField { * to a new ByteBuffer for UAVTalk. It also converts from the java standard (big endian) * to the arm/uavtalk standard (little endian) * @param dataOut - * @return -] + * @return the number of bytes added * @throws Exception */ public int pack(ByteBuffer dataOut) throws Exception { //QMutexLocker locker(obj->getMutex()); From a9b28687eafb2dca1d91a68e036f58a8f49ce251 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 00:03:20 -0600 Subject: [PATCH 200/543] More work on the java UAVObject implementation --- .../org/openpilot/uavtalk/UAVDataObject.java | 93 ++- .../org/openpilot/uavtalk/UAVMetaObject.java | 140 +++-- .../src/org/openpilot/uavtalk/UAVObject.java | 581 +++++++++--------- .../org/openpilot/uavtalk/UAVObjectField.java | 35 +- .../openpilot/uavtalk/UAVObjectManager.java | 30 +- 5 files changed, 497 insertions(+), 382 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index a2e6acf9e..f0a2248f5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -9,39 +9,78 @@ public abstract class UAVDataObject extends UAVObject { * @param isSet * @param name */ - public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) { + public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) throws Exception { super(objID, isSingleInst, name); + mobj = null; + this.isSet = isSet; } - - public abstract void initialize(int instID, UAVMetaObject mobj); - - public abstract void initialize(UAVMetaObject mobj); - - Boolean isSettings() { - return null; + /** + * Initialize instance ID and assign a metaobject + */ + public void initialize(int instID, UAVMetaObject mobj) + { + //QMutexLocker locker(mutex); + this.mobj = mobj; + super.initialize(instID); + } + + /** + * Assign a metaobject + */ + public void initialize(UAVMetaObject mobj) + { + //QMutexLocker locker(mutex); + this.mobj = mobj; + } + + /** + * Returns true if this is a data object holding module settings + */ + public boolean isSettings() + { + return isSet; + } + + /** + * Set the object's metadata + */ + public void setMetadata(Metadata mdata) + { + if ( mobj != null ) + { + mobj.setData(mdata); + } + } + + /** + * Get the object's metadata + */ + public Metadata getMetadata() + { + if ( mobj != null) + { + return mobj.getData(); + } + else + { + return getDefaultMetadata(); + } + } + + /** + * Get the metaobject + */ + public UAVMetaObject getMetaObject() + { + return mobj; } - - UAVMetaObject getMetaObject() { - return null; - } + // TODO: Make abstract public UAVDataObject clone(int instID) { - try { - return (UAVDataObject) super.clone(); - } catch (CloneNotSupportedException e) { - // TODO Auto-generated catch block - e.printStackTrace(); - } - return null; + return (UAVDataObject) super.clone(); } -public: - static int OBJID = $(OBJIDHEX); - static String NAME; - static String DESCRIPTION; - static boolean ISSINGLEINST = $(ISSINGLEINST); - static boolean ISSETTINGS = $(ISSETTINGS); - static int NUMBYTES = sizeof(DataFields); - + private UAVMetaObject mobj; + private boolean isSet; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index 9c2e3b12d..70e661d46 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -1,76 +1,116 @@ package org.openpilot.uavtalk; +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; + public class UAVMetaObject extends UAVObject { - public UAVMetaObject(int objID, String name, UAVDataObject parent) { + public UAVMetaObject(int objID, String name, UAVDataObject parent) throws Exception { super(objID, true, name); this.parent = parent; - - ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - ownMetadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - ownMetadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - ownMetadata.flightTelemetryUpdatePeriod = 0; - ownMetadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - ownMetadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - ownMetadata.gcsTelemetryUpdatePeriod = 0; - ownMetadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - ownMetadata.loggingUpdatePeriod = 0; - + + ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + ownMetadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + ownMetadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.flightTelemetryUpdatePeriod = 0; + ownMetadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + ownMetadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.gcsTelemetryUpdatePeriod = 0; + ownMetadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.loggingUpdatePeriod = 0; + + // Setup fields + List boolEnum = new ArrayList(); + boolEnum.add("False"); + boolEnum.add("True"); + + List updateModeEnum = new ArrayList(); + updateModeEnum.add("Periodic"); + updateModeEnum.add("On Change"); + updateModeEnum.add("Manual"); + updateModeEnum.add("Never"); + + List accessModeEnum = new ArrayList(); + accessModeEnum.add("Read/Write"); + accessModeEnum.add("Read Only"); + + List fields = new ArrayList(); + fields.add( new UAVObjectField("Flight Access Mode", "", UAVObjectField.FieldType.ENUM, 1, accessModeEnum) ); + fields.add( new UAVObjectField("GCS Access Mode", "", UAVObjectField.FieldType.ENUM, 1, accessModeEnum) ); + fields.add( new UAVObjectField("Flight Telemetry Acked", "", UAVObjectField.FieldType.ENUM, 1, boolEnum) ); + fields.add( new UAVObjectField("Flight Telemetry Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); + fields.add( new UAVObjectField("Flight Telemetry Update Period", "", UAVObjectField.FieldType.UINT32, 1, null) ); + fields.add( new UAVObjectField("GCS Telemetry Acked", "", UAVObjectField.FieldType.ENUM, 1, boolEnum) ); + fields.add( new UAVObjectField("GCS Telemetry Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); + fields.add( new UAVObjectField("GCS Telemetry Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); + fields.add( new UAVObjectField("Logging Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); + fields.add( new UAVObjectField("Logging Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); + + // Initialize parent + super.initialize(0); + super.initializeFields(fields, ByteBuffer.allocate(10), 10); + + // Setup metadata of parent + parentMetadata = parent.getDefaultMetadata(); } - UAVObject getParentObject() { + /** + * Get the parent object + */ + public UAVObject getParentObject() + { return parent; } - @Override - public void deserialize(byte[] arr, int offset) { - // TODO Auto-generated method stub - + /** + * Set the metadata of the metaobject, this function will + * do nothing since metaobjects have read-only metadata. + */ + public void setMetadata(Metadata mdata) + { + return; // can not update metaobject's metadata } - @Override - public Metadata getMetadata() { + /** + * Get the metadata of the metaobject + */ + public Metadata getMetadata() + { return ownMetadata; } - @Override - public Metadata getDefaultMetadata() { - return ownMetadata; + /** + * Get the default metadata + */ + public Metadata getDefaultMetadata() + { + return ownMetadata; } - @Override - public String getDescription() { - // TODO Auto-generated method stub - return null; + /** + * Set the metadata held by the metaobject + */ + public void setData(Metadata mdata) + { + //QMutexLocker locker(mutex); + parentMetadata = mdata; + // TODO: Callbacks + // emit objectUpdatedAuto(this); // trigger object updated event + // emit objectUpdated(this); } - @Override - public int getObjID() { - // TODO Auto-generated method stub - return 0; + /** + * Get the metadata held by the metaobject + */ + public Metadata getData() + { +// QMutexLocker locker(mutex); + return parentMetadata; } - @Override - public String getObjName() { - // TODO Auto-generated method stub - return null; - } - @Override - public byte[] serialize() { - // TODO Auto-generated method stub - return null; - } - - - public UAVMetaObject(quint32 objID, const QString& name, UAVObject* parent); - UAVObject* getParentObject(); - void setMetadata(const Metadata& mdata); - void setData(const Metadata& mdata); - Metadata getData(); - - private UAVObject parent; private Metadata ownMetadata; private Metadata parentMetadata; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index f987a03a9..926440805 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -6,241 +6,274 @@ import java.util.ListIterator; public abstract class UAVObject { - /** * Object update mode */ public enum UpdateMode { - UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ + UPDATEMODE_PERIODIC, /** + * Automatically update object at periodic + * intervals + */ UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ - UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ - UPDATEMODE_NEVER /** Object is never updated */ - } ; + UPDATEMODE_MANUAL, /** + * Manually update object, by calling the updated() + * function + */ + UPDATEMODE_NEVER + /** Object is never updated */ + }; /** * Access mode */ - public enum AccessMode{ - ACCESS_READWRITE, - ACCESS_READONLY - } ; + public enum AccessMode { + ACCESS_READWRITE, ACCESS_READONLY + }; /** * Access mode */ - public enum Acked{ - FALSE, - TRUE - } ; + public enum Acked { + FALSE, TRUE + }; - protected final class Metadata { - public AccessMode flightAccess; /** Defines the access level for the local flight transactions (readonly and readwrite) */ - public AccessMode gcsAccess; /** Defines the access level for the local GCS transactions (readonly and readwrite) */ - public Acked flightTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - public UpdateMode flightTelemetryUpdateMode; /** Update mode used by the autopilot (UpdateMode) */ - public int flightTelemetryUpdatePeriod; /** Update period used by the autopilot (only if telemetry mode is PERIODIC) */ - public Acked gcsTelemetryAcked; /** Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) */ - public UpdateMode gcsTelemetryUpdateMode; /** Update mode used by the GCS (UpdateMode) */ - public int gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ - public UpdateMode loggingUpdateMode; /** Update mode used by the logging module (UpdateMode) */ - public int loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ - } ; + public final class Metadata { + public AccessMode flightAccess; + /** + * Defines the access level for the local flight transactions (readonly + * and readwrite) + */ + public AccessMode gcsAccess; + /** + * Defines the access level for the local GCS transactions (readonly and + * readwrite) + */ + public Acked flightTelemetryAcked; + /** + * Defines if an ack is required for the transactions of this object + * (1:acked, 0:not acked) + */ + public UpdateMode flightTelemetryUpdateMode; + /** Update mode used by the autopilot (UpdateMode) */ + public int flightTelemetryUpdatePeriod; + /** + * Update period used by the autopilot (only if telemetry mode is + * PERIODIC) + */ + public Acked gcsTelemetryAcked; + /** + * Defines if an ack is required for the transactions of this object + * (1:acked, 0:not acked) + */ + public UpdateMode gcsTelemetryUpdateMode; + /** Update mode used by the GCS (UpdateMode) */ + public int gcsTelemetryUpdatePeriod; + /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + public UpdateMode loggingUpdateMode; + /** Update mode used by the logging module (UpdateMode) */ + public int loggingUpdatePeriod; + /** + * Update period used by the logging module (only if logging mode is + * PERIODIC) + */ + }; public UAVObject(int objID, Boolean isSingleInst, String name) { this.objID = objID; this.instID = 0; this.isSingleInst = isSingleInst; this.name = name; - // this.mutex = new QMutex(QMutex::Recursive); + // this.mutex = new QMutex(QMutex::Recursive); }; public void initialize(int instID) { - //QMutexLocker locker(mutex); + // QMutexLocker locker(mutex); this.instID = instID; } /** * Initialize objects' data fields - * @param fields List of fields held by the object - * @param data Pointer to that actual object data, this is needed by the fields to access the data - * @param numBytes Number of bytes in the object (total, including all fields) - * @throws Exception When unable to unpack a field + * + * @param fields + * List of fields held by the object + * @param data + * Pointer to that actual object data, this is needed by the + * fields to access the data + * @param numBytes + * Number of bytes in the object (total, including all fields) + * @throws Exception + * When unable to unpack a field */ - public void initializeFields(List fields, ByteBuffer data, int numBytes) throws Exception - { - // TODO: QMutexLocker locker(mutex); + public void initializeFields(List fields, ByteBuffer data, + int numBytes) throws Exception { + // TODO: QMutexLocker locker(mutex); this.numBytes = numBytes; - this.data = data; +// this.data = data; this.fields = fields; // Initialize fields - for (int n = 0; n < fields.size(); ++n) - { + for (int n = 0; n < fields.size(); ++n) { fields.get(n).initialize(this); } - unpack(data); +// unpack(data); } /** * Get the object ID */ - public int getObjID() - { + public int getObjID() { return objID; } /** * Get the instance ID */ - public int getInstID() - { + public int getInstID() { return instID; } /** * Returns true if this is a single instance object */ - public boolean isSingleInstance() - { + public boolean isSingleInstance() { return isSingleInst; } /** * Get the name of the object */ - public String getName() - { + public String getName() { return name; } /** * Get the description of the object + * * @return The description of the object */ - public String getDescription() - { + public String getDescription() { return description; } /** * Set the description of the object - * @param The description of the object - * @return + * + * @param The + * description of the object + * @return */ - public void setDescription(String description) - { + public void setDescription(String description) { this.description = description; } - /** * Get the total number of bytes of the object's data */ - public int getNumBytes() - { + public int getNumBytes() { return numBytes; } - // /** - // * Request that this object is updated with the latest values from the autopilot - // */ - // /* void UAVObject::requestUpdate() - // { - // emit updateRequested(this); - // } */ + // /** + // * Request that this object is updated with the latest values from the + // autopilot + // */ + // /* void UAVObject::requestUpdate() + // { + // emit updateRequested(this); + // } */ // - // /** - // * Signal that the object has been updated - // */ - // /* void UAVObject::updated() - // { - // emit objectUpdatedManual(this); - // emit objectUpdated(this); - // } */ + // /** + // * Signal that the object has been updated + // */ + // /* void UAVObject::updated() + // { + // emit objectUpdatedManual(this); + // emit objectUpdated(this); + // } */ // - // /** - // * Lock mutex of this object - // */ - // /* void UAVObject::lock() - // { - // mutex->lock(); - // } */ + // /** + // * Lock mutex of this object + // */ + // /* void UAVObject::lock() + // { + // mutex->lock(); + // } */ // - // /** - // * Lock mutex of this object - // */ - // /* void UAVObject::lock(int timeoutMs) - // { - // mutex->tryLock(timeoutMs); - // } */ + // /** + // * Lock mutex of this object + // */ + // /* void UAVObject::lock(int timeoutMs) + // { + // mutex->tryLock(timeoutMs); + // } */ // - // /** - // * Unlock mutex of this object - // */ - // /* void UAVObject::unlock() - // { - // mutex->unlock(); - // } */ + // /** + // * Unlock mutex of this object + // */ + // /* void UAVObject::unlock() + // { + // mutex->unlock(); + // } */ // - // /** - // * Get object's mutex - // */ - // QMutex* UAVObject::getMutex() - // { - // return mutex; - // } + // /** + // * Get object's mutex + // */ + // QMutex* UAVObject::getMutex() + // { + // return mutex; + // } /** * Get the number of fields held by this object */ - public int getNumFields() - { - //QMutexLocker locker(mutex); + public int getNumFields() { + // QMutexLocker locker(mutex); return fields.size(); } /** * Get the object's fields */ - public List getFields() - { - //QMutexLocker locker(mutex); + public List getFields() { + // QMutexLocker locker(mutex); return fields; } /** * Get a specific field - * @throws Exception + * + * @throws Exception * @returns The field or NULL if not found */ - public UAVObjectField getField(String name) throws Exception - { - //QMutexLocker locker(mutex); + public UAVObjectField getField(String name) { + // QMutexLocker locker(mutex); // Look for field ListIterator li = fields.listIterator(); - while(li.hasNext()) { + while (li.hasNext()) { UAVObjectField field = li.next(); - if(field.getName().equals(name)) + if (field.getName().equals(name)) return field; } - throw new Exception("Field not found"); + //throw new Exception("Field not found"); + return null; } /** * Pack the object data into a byte array - * @param dataOut ByteBuffer to receive the data. - * @throws Exception + * + * @param dataOut + * ByteBuffer to receive the data. + * @throws Exception * @returns The number of bytes copied * @note The array must already have enough space allocated for the object */ - public int pack(ByteBuffer dataOut) throws Exception - { + public int pack(ByteBuffer dataOut) throws Exception { // QMutexLocker locker(mutex); - if(dataOut.remaining() < getNumBytes()) + if (dataOut.remaining() < getNumBytes()) throw new Exception("Not enough bytes in ByteBuffer to pack object"); int numBytes = 0; ListIterator li = fields.listIterator(); - while(li.hasNext()) { + while (li.hasNext()) { UAVObjectField field = li.next(); numBytes += field.pack(dataOut); } @@ -249,232 +282,232 @@ public abstract class UAVObject { /** * Unpack the object data from a byte array - * @param dataIn The ByteBuffer to pull data from - * @throws Exception + * + * @param dataIn + * The ByteBuffer to pull data from + * @throws Exception * @returns The number of bytes copied */ - public int unpack(ByteBuffer dataIn) throws Exception - { + public int unpack(ByteBuffer dataIn) throws Exception { + if( dataIn == null ) + return 0; + System.out.println( dataIn.toString() ); // QMutexLocker locker(mutex); int numBytes = 0; ListIterator li = fields.listIterator(); - while(li.hasNext()) { + while (li.hasNext()) { UAVObjectField field = li.next(); + System.out.println(field.toString()); numBytes += field.unpack(dataIn); } return numBytes; // TODO: Callbacks - //emit objectUnpacked(this); // trigger object updated event - //emit objectUpdated(this); + // emit objectUnpacked(this); // trigger object updated event + // emit objectUpdated(this); } - // /** - // * Save the object data to the file. - // * The file will be created in the current directory - // * and its name will be the same as the object with - // * the .uavobj extension. - // * @returns True on success, false on failure - // */ - // bool UAVObject::save() - // { - // QMutexLocker locker(mutex); + // /** + // * Save the object data to the file. + // * The file will be created in the current directory + // * and its name will be the same as the object with + // * the .uavobj extension. + // * @returns True on success, false on failure + // */ + // bool UAVObject::save() + // { + // QMutexLocker locker(mutex); // - // // Open file - // QFile file(name + ".uavobj"); - // if (!file.open(QFile::WriteOnly)) - // { - // return false; - // } + // // Open file + // QFile file(name + ".uavobj"); + // if (!file.open(QFile::WriteOnly)) + // { + // return false; + // } // - // // Write object - // if ( !save(file) ) - // { - // return false; - // } + // // Write object + // if ( !save(file) ) + // { + // return false; + // } // - // // Close file - // file.close(); - // return true; - // } + // // Close file + // file.close(); + // return true; + // } // - // /** - // * Save the object data to the file. - // * The file is expected to be already open for writting. - // * The data will be appended and the file will not be closed. - // * @returns True on success, false on failure - // */ - // bool UAVObject::save(QFile& file) - // { - // QMutexLocker locker(mutex); - // quint8 buffer[numBytes]; - // quint8 tmpId[4]; + // /** + // * Save the object data to the file. + // * The file is expected to be already open for writting. + // * The data will be appended and the file will not be closed. + // * @returns True on success, false on failure + // */ + // bool UAVObject::save(QFile& file) + // { + // QMutexLocker locker(mutex); + // quint8 buffer[numBytes]; + // quint8 tmpId[4]; // - // // Write the object ID - // qToLittleEndian(objID, tmpId); - // if ( file.write((const char*)tmpId, 4) == -1 ) - // { - // return false; - // } + // // Write the object ID + // qToLittleEndian(objID, tmpId); + // if ( file.write((const char*)tmpId, 4) == -1 ) + // { + // return false; + // } // - // // Write the instance ID - // if (!isSingleInst) - // { - // qToLittleEndian(instID, tmpId); - // if ( file.write((const char*)tmpId, 2) == -1 ) - // { - // return false; - // } - // } + // // Write the instance ID + // if (!isSingleInst) + // { + // qToLittleEndian(instID, tmpId); + // if ( file.write((const char*)tmpId, 2) == -1 ) + // { + // return false; + // } + // } // - // // Write the data - // pack(buffer); - // if ( file.write((const char*)buffer, numBytes) == -1 ) - // { - // return false; - // } + // // Write the data + // pack(buffer); + // if ( file.write((const char*)buffer, numBytes) == -1 ) + // { + // return false; + // } // - // // Done - // return true; - // } + // // Done + // return true; + // } // - // /** - // * Load the object data from a file. - // * The file will be openned in the current directory - // * and its name will be the same as the object with - // * the .uavobj extension. - // * @returns True on success, false on failure - // */ - // bool UAVObject::load() - // { - // QMutexLocker locker(mutex); + // /** + // * Load the object data from a file. + // * The file will be openned in the current directory + // * and its name will be the same as the object with + // * the .uavobj extension. + // * @returns True on success, false on failure + // */ + // bool UAVObject::load() + // { + // QMutexLocker locker(mutex); // - // // Open file - // QFile file(name + ".uavobj"); - // if (!file.open(QFile::ReadOnly)) - // { - // return false; - // } + // // Open file + // QFile file(name + ".uavobj"); + // if (!file.open(QFile::ReadOnly)) + // { + // return false; + // } // - // // Load object - // if ( !load(file) ) - // { - // return false; - // } + // // Load object + // if ( !load(file) ) + // { + // return false; + // } // - // // Close file - // file.close(); - // return true; - // } + // // Close file + // file.close(); + // return true; + // } // - // /** - // * Load the object data from file. - // * The file is expected to be already open for reading. - // * The data will be read and the file will not be closed. - // * @returns True on success, false on failure - // */ - // bool UAVObject::load(QFile& file) - // { - // QMutexLocker locker(mutex); - // quint8 buffer[numBytes]; - // quint8 tmpId[4]; + // /** + // * Load the object data from file. + // * The file is expected to be already open for reading. + // * The data will be read and the file will not be closed. + // * @returns True on success, false on failure + // */ + // bool UAVObject::load(QFile& file) + // { + // QMutexLocker locker(mutex); + // quint8 buffer[numBytes]; + // quint8 tmpId[4]; // - // // Read the object ID - // if ( file.read((char*)tmpId, 4) != 4 ) - // { - // return false; - // } + // // Read the object ID + // if ( file.read((char*)tmpId, 4) != 4 ) + // { + // return false; + // } // - // // Check that the IDs match - // if (qFromLittleEndian(tmpId) != objID) - // { - // return false; - // } + // // Check that the IDs match + // if (qFromLittleEndian(tmpId) != objID) + // { + // return false; + // } // - // // Read the instance ID - // if ( file.read((char*)tmpId, 2) != 2 ) - // { - // return false; - // } + // // Read the instance ID + // if ( file.read((char*)tmpId, 2) != 2 ) + // { + // return false; + // } // - // // Check that the IDs match - // if (qFromLittleEndian(tmpId) != instID) - // { - // return false; - // } + // // Check that the IDs match + // if (qFromLittleEndian(tmpId) != instID) + // { + // return false; + // } // - // // Read and unpack the data - // if ( file.read((char*)buffer, numBytes) != numBytes ) - // { - // return false; - // } - // unpack(buffer); + // // Read and unpack the data + // if ( file.read((char*)buffer, numBytes) != numBytes ) + // { + // return false; + // } + // unpack(buffer); // - // // Done - // return true; - // } + // // Done + // return true; + // } /** * Return a string with the object information */ @Override - public String toString() - { + public String toString() { return toStringBrief() + toStringData(); } /** * Return a string with the object information (only the header) */ - public String toStringBrief() - { - return String.format("%1 (ID: %2, InstID: %3, NumBytes: %4, SInst: %5)\n", - getName(), - getObjID(), - getInstID(), - getNumBytes(), - isSingleInstance()); + public String toStringBrief() { + return getName() + " ( " + getObjID() + " " + getInstID() + " " + getNumBytes() + ")\n"; + // getName(), getObjID(), getInstID(), getNumBytes(), + // isSingleInstance()); } /** * Return a string with the object information (only the data) */ - public String toStringData() - { + public String toStringData() { String s = new String(); ListIterator li = fields.listIterator(); - while(li.hasNext()) { + while (li.hasNext()) { UAVObjectField field = li.next(); s += field.toString(); } return s; } - // /** - // * Emit the transactionCompleted event (used by the UAVTalk plugin) - // */ - // void UAVObject::emitTransactionCompleted(bool success) - // { - // emit transactionCompleted(this, success); - // } + // /** + // * Emit the transactionCompleted event (used by the UAVTalk plugin) + // */ + // void UAVObject::emitTransactionCompleted(bool success) + // { + // emit transactionCompleted(this, success); + // } - /** + /** * Java specific functions */ public UAVObject clone() { return (UAVObject) clone(); } + /** * Abstract functions */ public abstract void setMetadata(Metadata mdata); + public abstract Metadata getMetadata(); + public abstract Metadata getDefaultMetadata(); - public abstract UAVDataObject clone(int instID); - protected abstract void setDefaultFieldValues(); /** * Private data for the object, common to all - */ + */ protected int objID; protected int instID; protected boolean isSingleInst; @@ -482,6 +515,6 @@ public abstract class UAVObject { protected String description; protected int numBytes; // TODO: QMutex* mutex; - protected ByteBuffer data; +// protected ByteBuffer data; protected List fields; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index c7c774199..b37c992fb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -248,34 +248,37 @@ public class UAVObjectField { return null; } - public void setValue(Object data) throws Exception { setValue(data,0); } - public void setValue(Object data, int index) throws Exception { + public void setValue(Object data) { setValue(data,0); } + public void setValue(Object data, int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds if ( index >= numElements ) - throw new Exception("Index out of bounds"); + //throw new Exception("Index out of bounds"); System.out.println(data.toString()); System.out.println(this.data.toString()); // Get metadata - //UAVObject.Metadata mdata = obj.getMetadata(); + UAVObject.Metadata mdata = obj.getMetadata(); // Update value if the access mode permits - if ( true ) //mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) + if ( mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) { - ByteBuffer bbuf = ByteBuffer.allocate(numBytesPerElement); switch (type) { case INT8: + data = new Integer((Byte) data); case INT16: + data = new Integer((Short) data); case INT32: { List l = (List) this.data; - l.set(index, (Integer) data); + l.set(index,(Integer) data); break; } case UINT8: + data = new Integer((Byte) data); case UINT16: + data = new Integer((Short) data); case UINT32: { List l = (List) this.data; @@ -291,14 +294,14 @@ public class UAVObjectField { case ENUM: { byte val = (byte) options.indexOf((String) data); - if(val < 0) throw new Exception("Enumerated value not found"); + //if(val < 0) throw new Exception("Enumerated value not found"); List l = (List) this.data; l.set(index, val); break; } case STRING: { - throw new Exception("Sorry I haven't implemented strings yet"); + //throw new Exception("Sorry I haven't implemented strings yet"); } } } @@ -309,24 +312,24 @@ public class UAVObjectField { return Double.valueOf((Double) getValue(index)); } - void setDouble(double value) throws Exception { setDouble(value, 0); }; - void setDouble(double value, int index) throws Exception { + public void setDouble(double value) throws Exception { setDouble(value, 0); }; + public void setDouble(double value, int index) throws Exception { setValue(value, index); } - int getDataOffset() { + public int getDataOffset() { return offset; } - int getNumBytes() { + public int getNumBytes() { return numBytesPerElement * numElements; } - int getNumBytesElement() { + public int getNumBytesElement() { return numBytesPerElement; } - boolean isNumeric() { + public boolean isNumeric() { switch (type) { case INT8: @@ -352,7 +355,7 @@ public class UAVObjectField { } } - boolean isText() { + public boolean isText() { switch (type) { case INT8: diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 3091595f0..d75b14b85 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -21,8 +21,9 @@ public class UAVObjectManager { * A new instance can be created directly by instantiating a new object or by calling clone() of * an existing object. The object will be registered and will be properly initialized so that it can accept * updates. + * @throws Exception */ - Boolean registerObject(UAVDataObject obj) + public boolean registerObject(UAVDataObject obj) throws Exception { // QMutexLocker locker(mutex); @@ -126,7 +127,7 @@ public class UAVObjectManager { return true; } - void addObject(UAVObject obj) + public void addObject(UAVObject obj) { // Add to list List ls = new ArrayList(); @@ -139,7 +140,7 @@ public class UAVObjectManager { * Get all objects. A two dimentional QList is returned. Objects are grouped by * instances of the same object type. */ - List> getObjects() + public List> getObjects() { //QMutexLocker locker(mutex); return objects; @@ -148,7 +149,7 @@ public class UAVObjectManager { /** * Same as getObjects() but will only return DataObjects. */ - List< List > getDataObjects() + public List< List > getDataObjects() { return new ArrayList>(); @@ -186,7 +187,7 @@ public class UAVObjectManager { /** * Same as getObjects() but will only return MetaObjects. */ - List > getMetaObjects() + public List > getMetaObjects() { return new ArrayList< List >(); /* @@ -227,7 +228,7 @@ public class UAVObjectManager { * Get a specific object given its name and instance ID * @returns The object is found or NULL if not */ - UAVObject getObject(String name, int instId) + public UAVObject getObject(String name, int instId) { return getObject(name, 0, instId); } @@ -236,7 +237,7 @@ public class UAVObjectManager { * Get a specific object given its object and instance ID * @returns The object is found or NULL if not */ - UAVObject getObject(int objId, int instId) + public UAVObject getObject(int objId, int instId) { return getObject(null, objId, instId); } @@ -244,7 +245,7 @@ public class UAVObjectManager { /** * Helper function for the public getObject() functions. */ - UAVObject getObject(String name, int objId, int instId) + public UAVObject getObject(String name, int objId, int instId) { //QMutexLocker locker(mutex); // Check if this object type is already in the list @@ -271,7 +272,7 @@ public class UAVObjectManager { /** * Get all the instances of the object specified by name */ - List getObjectInstances(String name) + public List getObjectInstances(String name) { return getObjectInstances(name, 0); } @@ -279,7 +280,7 @@ public class UAVObjectManager { /** * Get all the instances of the object specified by its ID */ - List getObjectInstances(int objId) + public List getObjectInstances(int objId) { return getObjectInstances(null, objId); } @@ -287,7 +288,7 @@ public class UAVObjectManager { /** * Helper function for the public getObjectInstances() */ - List getObjectInstances(String name, int objId) + public List getObjectInstances(String name, int objId) { //QMutexLocker locker(mutex); // Check if this object type is already in the list @@ -307,7 +308,7 @@ public class UAVObjectManager { /** * Get the number of instances for an object given its name */ - int getNumInstances(String name) + public int getNumInstances(String name) { return getNumInstances(name, 0); } @@ -315,7 +316,7 @@ public class UAVObjectManager { /** * Get the number of instances for an object given its ID */ - int getNumInstances(int objId) + public int getNumInstances(int objId) { return getNumInstances(null, objId); } @@ -323,10 +324,9 @@ public class UAVObjectManager { /** * Helper function for public getNumInstances */ - int getNumInstances(String name, int objId) + public int getNumInstances(String name, int objId) { return getObjectInstances(name,objId).size(); } - } From 9a4c1586906a80e26a5cba1dde33c2f1cde53222 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 00:03:46 -0600 Subject: [PATCH 201/543] Java autogenerated code to be more compatible with gcs code --- .../templates/uavobjecttemplate.java | 127 +++-- .../java/uavobjectgeneratorjava.cpp | 434 ++++++++---------- .../generators/java/uavobjectgeneratorjava.h | 16 +- 3 files changed, 278 insertions(+), 299 deletions(-) diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index fa09f782f..af8f48fce 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -28,61 +28,110 @@ package org.openpilot.uavtalk.uavobjects; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVMetaObject; -import org.openpilot.uavtalk.UAVObjectField; +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVMetaObject; +import org.openpilot.uavtalk.UAVObjectField; /** $(DESCRIPTION) generated from $(XMLFILE) -**/ + **/ public class $(NAME) extends UAVDataObject { + public $(NAME)() throws Exception { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + $(FIELDSINIT) - public $(NAME) (int objID, Boolean isSingleInst, Boolean isSet, String name) { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - } + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytesElement(); + } + NUMBYTES = numBytes; + - public void setGeneratedMetaData() { + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } - getMetaData().gcsAccess = UAVObject.AccessMode.$(GCSACCESS); - getMetaData().gcsTelemetryAcked = UAVObject.Acked.$(GCSTELEM_ACKEDTF); - getMetaData().gcsTelemetryUpdateMode = UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE); - getMetaData().gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.$(GCSACCESS); + metadata.gcsTelemetryAcked = UAVObject.Acked.$(GCSTELEM_ACKEDTF); + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE); + metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - getMetaData().flightAccess = UAVObject.AccessMode.$(FLIGHTACCESS); - getMetaData().flightTelemetryAcked = UAVObject.Acked.$(FLIGHTTELEM_ACKEDTF); - getMetaData().flightTelemetryUpdateMode = UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE); - getMetaData().flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); + metadata.flightAccess = UAVObject.AccessMode.$(FLIGHTACCESS); + metadata.flightTelemetryAcked = UAVObject.Acked.$(FLIGHTTELEM_ACKEDTF); + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE); + metadata.flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - getMetaData().loggingUpdateMode = UAVObject.UpdateMode.$(LOGGING_UPDATEMODE); - getMetaData().loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + metadata.loggingUpdateMode = UAVObject.UpdateMode.$(LOGGING_UPDATEMODE); + metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + return metadata; + } - } - - public int getObjID() { - return $(OBJIDHEX); - } - - public String getObjName() { - return "$(NAME)"; - } + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { +$(INITFIELDS) + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + $(NAME) obj = new $(NAME)(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public $(NAME) GetInstance(UAVObjectManager objMngr, int instID) + { + return ($(NAME))(objMngr.getObject($(NAME).OBJID, instID)); + } - public String getDescription() { - return "$(DESCRIPTION)"; - } -protected: // Constants - static final int OBJID = $(OBJIDHEX); - static final String NAME; - static final String DESCRIPTION; - static final boolean ISSINGLEINST = $(ISSINGLEINST); - static final boolean ISSETTINGS = $(ISSETTINGS); - static final int NUMBYTES = sizeof(DataFields); + protected static final int OBJID = $(OBJIDHEX); + protected static final String NAME = "$(NAME)"; + protected static String DESCRIPTION = "$(DESCRIPTION)"; + protected static final boolean ISSINGLEINST = $(ISSINGLEINST) == 1; + protected static final boolean ISSETTINGS = $(ISSETTINGS) == 1; + protected static int NUMBYTES = 0; -$(GETTERSETTER) } \ No newline at end of file diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index 6ac45a07a..ce436e6af 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -24,313 +24,245 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include #include "uavobjectgeneratorjava.h" using namespace std; bool UAVObjectGeneratorJava::generate(UAVObjectParser* parser,QString templatepath,QString outputpath) { - QDir javaTemplatePath = QDir( templatepath + QString(JAVA_TEMPLATE_DIR)); + fieldTypeStrCPP << "qint8" << "qint16" << "qint32" << + "quint8" << "quint16" << "quint32" << "float" << "quint8"; - javaCodePath = QDir ( outputpath + QString(JAVA_GENERATED_DIR)); + fieldTypeStrCPPClass << "INT8" << "INT16" << "INT32" + << "UINT8" << "UINT16" << "UINT32" << "FLOAT32" << "ENUM"; - javaCodeTemplate = readFile( javaTemplatePath.absoluteFilePath("uavobjecttemplate.java") ); - QString javaInitCodeTemplate = readFile( javaTemplatePath.absoluteFilePath("uavobjectsinittemplate.java") ); + javaCodePath = QDir( templatepath + QString(JAVA_TEMPLATE_DIR)); + javaOutputPath = QDir( outputpath + QString("java") ); + javaOutputPath.mkpath(javaOutputPath.absolutePath()); - if (javaCodeTemplate.isEmpty() || javaInitCodeTemplate.isEmpty()) { - std::cerr << "Problem reading java templates" << endl; + javaCodeTemplate = readFile( javaCodePath.absoluteFilePath("uavobjecttemplate.java") ); + QString javaInitTemplate = readFile( javaCodePath.absoluteFilePath("uavobjectsinittemplate.java") ); + + if (javaCodeTemplate.isEmpty() || javaInitTemplate.isEmpty()) { + std::cerr << "Problem reading java code templates" << endl; return false; } - QString javaObjInit,javaObjGetter; - javaCodePath.mkpath(javaCodePath.absolutePath() + "/uavobjects"); + QString objInc; + QString javaObjInit; for (int objidx = 0; objidx < parser->getNumObjects(); ++objidx) { ObjectInfo* info=parser->getObjectByIndex(objidx); process_object(info); - if (!javaObjInit.isNull()) - javaObjInit.append(",\n"); - - javaObjInit.append(" new " + info->name + "()"); - javaObjGetter.append(QString(" public static %1 get%1() { return (%1)uavobjects[%2];}\n").arg( info->name).arg(objidx)); + javaObjInit.append(" objMngr->registerObject( new " + info->name + "() );\n"); + objInc.append("#include \"" + info->namelc + ".h\"\n"); } - javaInitCodeTemplate.replace("$(OBJINIT)",javaObjInit); - javaInitCodeTemplate.replace("$(OBJGETTER)",javaObjGetter); - - replaceCommonTags(javaInitCodeTemplate); - - // Write the java object inialization files - bool res = writeFileIfDiffrent(javaCodePath.absolutePath() + "/UAVObjects.java", javaInitCodeTemplate ); + // Write the gcs object inialization files + javaInitTemplate.replace( QString("$(OBJINC)"), objInc); + javaInitTemplate.replace( QString("$(OBJINIT)"), javaObjInit); + bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/uavobjectsinit.java", javaInitTemplate ); if (!res) { - cerr << "Error: Could not write java init output files" << endl; + cout << "Error: Could not write output files" << endl; return false; } return true; // if we come here everything should be fine } -QString UAVObjectGeneratorJava::getFieldTypeStr(int type,bool as_obj) { - - switch(type) { - case FIELDTYPE_INT8: - return (QString(as_obj?"Byte":"byte")); - case FIELDTYPE_INT16: - case FIELDTYPE_INT32: - case FIELDTYPE_UINT8: - case FIELDTYPE_UINT16: - return (QString(as_obj?"Integer":"int")); - case FIELDTYPE_UINT32: - return (QString(as_obj?"Long":"long")); - case FIELDTYPE_FLOAT32: - return (QString(as_obj?"Float":"float")); - case FIELDTYPE_ENUM: - return (QString(as_obj?"Byte":"byte")); - default: - return QString("error: unknown type"); - } -} - -/** - * - * format a value from FieldInfo with a given index (idx) to a java code snippet - * - */ -QString UAVObjectGeneratorJava::formatJavaValue(FieldInfo* info,int idx) { - switch(info->type) { - case FIELDTYPE_ENUM: - return (info->name.toUpper() + QString("_") + info->defaultValues[idx].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "")); - case FIELDTYPE_FLOAT32: - return QString("%1f").arg( info->defaultValues[idx].toFloat() ); - default: - return QString("%1").arg( info->defaultValues[idx].toInt() ); - } -} - -QString UAVObjectGeneratorJava::QStringList2JavaArray(QStringList strl) { - QString csv=QString(); - for (int i = 0; i < strl.length(); i++){ - if (i!=0) - csv.append(QString(",")); - csv.append(QString("\"%1\"").arg(strl[i])); - } - return QString("new String[] { %1 }").arg(csv); -} - -QString UAVObjectGeneratorJava::serializeJavaValue(int type,QString name) -{ - QString res; - switch(type) { - case FIELDTYPE_ENUM: // OK - - case FIELDTYPE_INT8: - res=name; - break; - - case FIELDTYPE_UINT8: - res=QString("(byte)(%1&0xFF)").arg(name); - break; - - case FIELDTYPE_INT16: - case FIELDTYPE_UINT16: - res=QString("(byte)(("+name+">>0)&0xFF) , (byte)(("+name+">>8)&0xFF)"); - break; - - case FIELDTYPE_UINT32: - case FIELDTYPE_INT32: - res=QString("(byte)(("+name+">>0)&0xFF) , (byte)(("+name+">>8)&0xFF) , (byte)(("+name+">>16)&0xFF) , (byte)(("+name+">>24)&0xFF)"); - break; - - case FIELDTYPE_FLOAT32: - res=QString("(byte)((Float.floatToIntBits("+name+")>>0)&0xFF) , (byte)((Float.floatToIntBits("+name+")>>8)&0xFF) , (byte)((Float.floatToIntBits("+name+")>>16)&0xFF) , (byte)((Float.floatToIntBits("+name+")>>24)&0xFF) "); // OK - break; - - default: - res=QString("unresolved type"); - break; - } - - return res; -} - -/** - * this function is used to build the deserializing code - */ -QString UAVObjectGeneratorJava::deSerializeJavaValue(int type,QString name) -{ - switch(type) { - case FIELDTYPE_ENUM: // OK - case FIELDTYPE_INT8: - return (name.append("=arr[pos++];\n")); - - case FIELDTYPE_UINT8: - return (name.append("=arr[pos++]&0xFF;\n")); /*test */ - - case FIELDTYPE_INT16: - case FIELDTYPE_UINT16: - return (name.append("=((arr[pos++]&0xff)<<0) | ((arr[pos++]&0xff)<<8) ;\n")); /* test */ - - case FIELDTYPE_UINT32: - case FIELDTYPE_INT32: - return (name.append("=((arr[pos++]&0xff)<<0) | ((arr[pos++]&0xff)<<8) | ((arr[pos++]&0xff)<<16) | ((arr[pos++]&0xff)<<24) ;\n")); /*test */ - - case FIELDTYPE_FLOAT32: - return (name.append("=Float.intBitsToFloat(((arr[pos++]&0xff)<<0) | ((arr[pos++]&0xff)<<8) | ((arr[pos++]&0xff)<<16) | ((arr[pos++]&0xff)<<24) ); ")); // OK - - default: - cout << "Warning: unresolved type " << type << " for " << name.toStdString() << endl; - return(QString("unresolved type")); // will throw an arr when compiling then - } -} /** * Generate the java object files */ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) { - if (info == NULL) return false; + if (info == NULL) + return false; // Prepare output strings + QString outInclude = javaIncludeTemplate; QString outCode = javaCodeTemplate; // Replace common tags + replaceCommonTags(outInclude, info); replaceCommonTags(outCode, info); - QString type,fieldsinit,serialize_code,serialize_code_inner,deserialize_code,gettersetter; - - QString fielddesc=QString(" public final UAVObjectFieldDescription[] getFieldDescriptions() { return new UAVObjectFieldDescription[] {"); - QString fieldgetter=QString(" public Object getField(int fieldid,int arr_pos) { switch(fieldid) {\n"); - QString fieldsetter=QString(" public void setField(int fieldid,int arr_pos,Object obj) { switch(fieldid) {\n"); - - for (int n = 0; n < info->fields.length(); ++n) { - FieldInfo* act_field_info=info->fields[n]; - - bool is_array = info->fields[n]->numElements > 1; - type = getFieldTypeStr(act_field_info->type,false); // Determine type - - for (int enum_n = 0; enum_n < act_field_info->options.length(); ++enum_n) - fieldsinit.append(QString(" public final static byte %1 = %2;\n").arg(act_field_info->name.toUpper() + QString("_") + act_field_info->options[enum_n].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "")).arg(enum_n) ); - - fieldsinit.append(QString(" private ") + type); - - if ( is_array ) - fieldsinit.append(QString("[]")); - - fieldsinit.append(QString(" %1").arg(act_field_info->name)); - - if (!info->fields[n]->defaultValues.isEmpty()) { // if we have default vals - fieldsinit.append(QString("=")); - if ( is_array ) { - fieldsinit.append(QString("{")); - for (int val_n = 0; val_n < act_field_info->defaultValues.length(); ++val_n) - fieldsinit.append( ((val_n>0)?QString(","):QString() ) + formatJavaValue(act_field_info,val_n) ); - fieldsinit.append(QString("}")); - } - else - fieldsinit.append(formatJavaValue(act_field_info,0)); - } - else { - if ( is_array ) // when it is an array - fieldsinit.append(QString("= new ") + type + QString("[%1]").arg(info->fields[n]->numElements)); - } - - fieldsinit.append(QString(";\n")); - - if (n!=0) - serialize_code_inner.append(QString(",")); - - if ( is_array ) { - for (int el=0;elfields[n]->numElements;el++) { - if (el!=0) - serialize_code_inner.append(QString(",")); - - serialize_code_inner.append(serializeJavaValue(info->fields[n]->type,info->fields[n]->name+ QString("[%1]").arg(el))); - deserialize_code.append(deSerializeJavaValue(info->fields[n]->type,info->fields[n]->name+ QString("[%1]").arg(el))); - } - } - else { // no array - serialize_code_inner.append(serializeJavaValue(info->fields[n]->type,info->fields[n]->name)); - deserialize_code.append(deSerializeJavaValue(info->fields[n]->type,info->fields[n]->name)); - } - - serialize_code_inner.append(QString("//%1\n" ).arg(info->fields[n]->name)); - + // Replace the $(DATAFIELDS) tag + QString type; + QString fields; + for (int n = 0; n < info->fields.length(); ++n) + { // Determine type - type = getFieldTypeStr(act_field_info->type,false); - - QString typespec=type; - - if ( is_array ) { - typespec.append(QString("[]")); - fieldgetter.append(QString("case %1: return (Object)%2[arr_pos];\n").arg(n).arg(act_field_info->name)); - fieldsetter.append(QString("case %1: %2[arr_pos]=(%3)obj;break;\n").arg(n).arg(act_field_info->name).arg( getFieldTypeStr(act_field_info->type,true))); + type = fieldTypeStrCPP[info->fields[n]->type]; + // Append field + if ( info->fields[n]->numElements > 1 ) + { + fields.append( QString(" %1 %2[%3];\n").arg(type).arg(info->fields[n]->name) + .arg(info->fields[n]->numElements) ); } - else { // no array - fieldgetter.append(QString("case %1: return (Object)%2;\n").arg(n).arg(act_field_info->name)); - fieldsetter.append(QString("case %1: %2=(%3)obj;break;\n").arg(n).arg(act_field_info->name).arg(getFieldTypeStr(act_field_info->type,true))); + else + { + fields.append( QString(" %1 %2;\n").arg(type).arg(info->fields[n]->name) ); } + } + outInclude.replace(QString("$(DATAFIELDS)"), fields); + // Replace the $(FIELDSINIT) tag + QString finit; + for (int n = 0; n < info->fields.length(); ++n) + { + finit.append("\n"); - if (!act_field_info->units.isEmpty()) // when we have unit info - gettersetter.append(QString("\n /**\n * unit: %1\n */\n").arg(act_field_info->units)); + // Setup element names + QString varElemName = info->fields[n]->name + "ElemNames"; + finit.append( QString("\t\tList %1 = new ArrayList();\n").arg(varElemName) ); + QStringList elemNames = info->fields[n]->elementNames; + for (int m = 0; m < elemNames.length(); ++m) + finit.append( QString("\t\t%1.add(\"%2\");\n") + .arg(varElemName) + .arg(elemNames[m]) ); - gettersetter.append(QString(" public void set%1( %2 _%1 ) { %1=_%1; }\n").arg(act_field_info->name).arg(typespec)); - - if (n!=0) - fielddesc.append(QString("\t,")); - - fielddesc.append(QString("new UAVObjectFieldDescription(\"%1\",this.getObjID(),(byte)%2,(byte)%3,\"%4\",%5,%6)\n").arg(act_field_info->name).arg(n).arg(act_field_info->type).arg(act_field_info->units).arg(QStringList2JavaArray( act_field_info->options)).arg(QStringList2JavaArray( act_field_info->elementNames)) ); - - if (!act_field_info->units.isEmpty()) - gettersetter.append(QString("\n /**\n * unit: %1\n */\n").arg(act_field_info->units)); - - gettersetter.append(QString(" public ") + typespec); - - gettersetter.append(QString(" get%1() { return %1; }\n").arg(act_field_info->name)); - - if ( act_field_info->options.length()!=0) { - QString enumOptionsGetter=QString(" public final static String[] get%1EnumOptions() { return new String[] {").arg(act_field_info->name); - - // gettersetter.append(QString(" get%1s() { return %1; }\n").arg(act_field_info->name)); - for (int enum_n = 0; enum_n < act_field_info->options.length(); ++enum_n) { - if (enum_n!=0) - enumOptionsGetter.append(QString(",")); - enumOptionsGetter.append(QString("\"")+act_field_info->options[enum_n] +QString("\"")); + // Only for enum types + if (info->fields[n]->type == FIELDTYPE_ENUM) { + QString varOptionName = info->fields[n]->name + "EnumOptions"; + finit.append( QString("\t\tList %1 = new ArrayList();\n").arg(varOptionName) ); + QStringList options = info->fields[n]->options; + for (int m = 0; m < options.length(); ++m) + { + finit.append( QString("\t\t%1.add(\"%2\");\n") + .arg(varOptionName) + .arg(options[m]) ); } - - gettersetter.append(enumOptionsGetter+QString("};}\n")); + finit.append( QString("\t\tfields.add( new UAVObjectField(\"%1\", \"%2\", UAVObjectField.FieldType.ENUM, %3, %4) );\n") + .arg(info->fields[n]->name) + .arg(info->fields[n]->units) + .arg(varElemName) + .arg(varOptionName) ); } + // For all other types + else { + finit.append( QString("\t\tfields.add( new UAVObjectField(\"%1\", \"%2\", UAVObjectField.FieldType.%3, %4, null) );\n") + .arg(info->fields[n]->name) + .arg(info->fields[n]->units) + .arg(fieldTypeStrCPPClass[info->fields[n]->type]) + .arg(varElemName) ); + } + } + outCode.replace(QString("$(FIELDSINIT)"), finit); - if ( is_array ) { // when it is an array create getter for the element names - QString elementListGetter=QString(" public final static String[] get%1ElementNames() { return new String[] {").arg(act_field_info->name); + // Replace the $(DATAFIELDINFO) tag + QString name; + QString enums; + for (int n = 0; n < info->fields.length(); ++n) + { + enums.append(QString(" // Field %1 information\n").arg(info->fields[n]->name)); + // Only for enum types + if (info->fields[n]->type == FIELDTYPE_ENUM) + { + enums.append(QString(" /* Enumeration options for field %1 */\n").arg(info->fields[n]->name)); + enums.append(" typedef enum { "); + // Go through each option + QStringList options = info->fields[n]->options; + for (int m = 0; m < options.length(); ++m) { + QString s = (m != (options.length()-1)) ? "%1_%2=%3, " : "%1_%2=%3"; + enums.append( s.arg( info->fields[n]->name.toUpper() ) + .arg( options[m].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "") ) + .arg(m) ); + + } + enums.append( QString(" } %1Options;\n") + .arg( info->fields[n]->name ) ); + } + // Generate element names (only if field has more than one element) + if (info->fields[n]->numElements > 1 && !info->fields[n]->defaultElementNames) { + enums.append(QString(" /* Array element names for field %1 */\n").arg(info->fields[n]->name)); + enums.append(" typedef enum { "); + // Go through the element names QStringList elemNames = info->fields[n]->elementNames; for (int m = 0; m < elemNames.length(); ++m) { - gettersetter.append(QString(" public ") + type); - gettersetter.append(QString(" get%1%2() { return %1[%3]; }\n").arg(act_field_info->name).arg(elemNames[m]).arg(m)); - if (m!=0) - elementListGetter.append(QString(",")); + QString s = (m != (elemNames.length()-1)) ? "%1_%2=%3, " : "%1_%2=%3"; + enums.append( s.arg( info->fields[n]->name.toUpper() ) + .arg( elemNames[m].toUpper() ) + .arg(m) ); - elementListGetter.append(QString("\"") + elemNames[m]+QString("\"")); } - gettersetter.append(elementListGetter+QString("};}\n")); + enums.append( QString(" } %1Elem;\n") + .arg( info->fields[n]->name ) ); + } + // Generate array information + if (info->fields[n]->numElements > 1) { + enums.append(QString(" /* Number of elements for field %1 */\n").arg(info->fields[n]->name)); + enums.append( QString(" static const quint32 %1_NUMELEM = %2;\n") + .arg( info->fields[n]->name.toUpper() ) + .arg( info->fields[n]->numElements ) ); + } + } + outInclude.replace(QString("$(DATAFIELDINFO)"), enums); + + // Replace the $(INITFIELDS) tag + QString initfields; + for (int n = 0; n < info->fields.length(); ++n) + { + if (!info->fields[n]->defaultValues.isEmpty() ) + { + // For non-array fields + if ( info->fields[n]->numElements == 1) + { + if ( info->fields[n]->type == FIELDTYPE_ENUM ) + { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%2);\n") + .arg( info->fields[n]->name ) + .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[0] ) ) ); + } + else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) + { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%2);\n") + .arg( info->fields[n]->name ) + .arg( info->fields[n]->defaultValues[0].toFloat() ) ); + } + else + { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%2);\n") + .arg( info->fields[n]->name ) + .arg( info->fields[n]->defaultValues[0].toInt() ) ); + } + } + else + { + // Initialize all fields in the array + for (int idx = 0; idx < info->fields[n]->numElements; ++idx) + { + if ( info->fields[n]->type == FIELDTYPE_ENUM ) { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") + .arg( info->fields[n]->name ) + .arg( idx ) + .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[idx] ) ) ); + } + else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") + .arg( info->fields[n]->name ) + .arg( idx ) + .arg( info->fields[n]->defaultValues[idx].toFloat() ) ); + } + else { + initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") + .arg( info->fields[n]->name ) + .arg( idx ) + .arg( info->fields[n]->defaultValues[idx].toInt() ) ); + } + } + } } } - serialize_code.append(QString(" public byte[] serialize() { return new byte[]{%1 } ;}; \n ").arg(serialize_code_inner)); + outCode.replace(QString("$(INITFIELDS)"), initfields); - serialize_code.append(QString(" public void deserialize(byte[] arr,int offset) {\nsuper.deserialize(arr,offset);\n int pos=offset;\n%1 };\n").arg(deserialize_code)); - - outCode.replace(QString("$(FIELDSINIT)"), fieldsinit); - - fielddesc.append(QString("};}")); - fieldgetter.append(QString("};\n return null;\n}\n")); - fieldsetter.append(QString("};\n}\n")); - outCode.replace(QString("$(GETTERSETTER)"), gettersetter + serialize_code+ fielddesc + fieldgetter + fieldsetter); - - bool res = writeFileIfDiffrent(javaCodePath.absolutePath() + "/uavobjects/" + info->name + ".java", outCode ); + // Write the java code + bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/" + info->namelc + ".java", outCode ); if (!res) { - cerr << "Error: Could not write java init output file " << info->name.toStdString()<< endl; + cout << "Error: Could not write gcs output files" << endl; return false; - } + } return true; } diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.h b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.h index 21fc4dc75..8d07484f6 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.h +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.h @@ -28,7 +28,7 @@ #define UAVOBJECTGENERATORJAVA_H #define JAVA_TEMPLATE_DIR "ground/openpilotgcs/src/libs/juavobjects/templates/" -#define JAVA_GENERATED_DIR "java/src/org/openpilot/uavtalk" +#define JAVA_CODE_DIR "java/src/org/openpilot/uavtalk" #include "../generator_common.h" @@ -38,14 +38,12 @@ public: bool generate(UAVObjectParser* gen,QString templatepath,QString outputpath); private: - QString javaCodeTemplate; - QDir javaCodePath; bool process_object(ObjectInfo* info); - QString formatJavaValue(FieldInfo* info,int idx); - QString QStringList2JavaArray(QStringList strl); - QString serializeJavaValue(int type,QString name); - QString deSerializeJavaValue(int type,QString name); - QString getFieldTypeStr(int type,bool as_obj); -}; + + QString javaCodeTemplate, javaIncludeTemplate; + QStringList fieldTypeStrCPP,fieldTypeStrCPPClass; + QDir javaCodePath; + QDir javaOutputPath; + }; #endif From 2238ca08046a33e0476e04be364914f16d8666a6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 00:56:56 -0600 Subject: [PATCH 202/543] Remove some debugging lines, also use Number interface instead of explicit Byte, Integer, Short etc in setValue/getValue --- .../src/org/openpilot/uavtalk/UAVObject.java | 5 +- .../org/openpilot/uavtalk/UAVObjectField.java | 118 +++++++++++------- 2 files changed, 77 insertions(+), 46 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 926440805..fe478cf2e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -114,7 +114,7 @@ public abstract class UAVObject { for (int n = 0; n < fields.size(); ++n) { fields.get(n).initialize(this); } -// unpack(data); + unpack(data); } /** @@ -291,13 +291,12 @@ public abstract class UAVObject { public int unpack(ByteBuffer dataIn) throws Exception { if( dataIn == null ) return 0; - System.out.println( dataIn.toString() ); + // QMutexLocker locker(mutex); int numBytes = 0; ListIterator li = fields.listIterator(); while (li.hasNext()) { UAVObjectField field = li.next(); - System.out.println(field.toString()); numBytes += field.unpack(dataIn); } return numBytes; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index b37c992fb..a9006e02f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -99,31 +99,43 @@ public class UAVObjectField { switch (type) { case INT8: - for (int index = 0; index < numElements; ++index) - dataOut.put((Byte) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.put(val.byteValue()); + } break; case INT16: - for (int index = 0; index < numElements; ++index) - dataOut.putShort((Short) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.putShort(val.shortValue()); + } break; case INT32: - for (int index = 0; index < numElements; ++index) - dataOut.putInt((Integer) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.putInt(val); + } break; case UINT8: // TODO: Deal properly with unsigned - for (int index = 0; index < numElements; ++index) - dataOut.put((Byte) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.put(val.byteValue()); + } break; case UINT16: // TODO: Deal properly with unsigned - for (int index = 0; index < numElements; ++index) - dataOut.putShort((Short) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.putShort(val.shortValue()); + } break; case UINT32: // TODO: Deal properly with unsigned - for (int index = 0; index < numElements; ++index) - dataOut.putInt((Integer) getValue(index)); + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.putInt(val); + } break; case FLOAT32: for (int index = 0; index < numElements; ++index) @@ -142,64 +154,93 @@ public class UAVObjectField { return getNumBytes(); } - public int unpack(ByteBuffer dataIn) throws Exception { + public int unpack(ByteBuffer dataIn) { // Unpack each element from input buffer dataIn.order(ByteOrder.LITTLE_ENDIAN); switch (type) { case INT8: + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Byte) dataIn.get(), index); + Byte val = dataIn.get(); + l.set(index, val.intValue()); } break; + } case INT16: + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Short) dataIn.getShort(), index); + Short val = dataIn.getShort(); + l.set(index, val.intValue()); } break; + } case INT32: + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Integer) dataIn.getInt(), index); + Integer val = dataIn.getInt(); + l.set(index, val.intValue()); } break; + } case UINT8: - // TODO: Deal with unsigned + // TOOD: Deal with unsigned + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Byte) dataIn.get(), index); + Byte val = dataIn.get(); + l.set(index, val.intValue()); } break; + } case UINT16: - // TODO: Deal with unsigned + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Short) dataIn.getShort(), index); + Short val = dataIn.getShort(); + l.set(index, val.intValue()); } break; + } case UINT32: - // TODO: Deal with unsigned + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Integer) dataIn.getInt(), index); + Integer val = dataIn.getInt(); + l.set(index, val.intValue()); } break; + } case FLOAT32: + { + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - setValue((Float) dataIn.getFloat(), index); + Float val = dataIn.getFloat(); + l.set(index, val); } break; + } case ENUM: + { List l = (List) data; for (int index = 0 ; index < numElements; ++index) { l.set(index, dataIn.get(index)); } break; + } case STRING: - throw new Exception("Strings not handled"); + // TODO: implement strings + //throw new Exception("Strings not handled"); } // Done return getNumBytes(); } - Object getValue() throws Exception { return getValue(0); }; - Object getValue(int index) throws Exception { + Object getValue() { return getValue(0); }; + Object getValue(int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds if ( index >= numElements ) @@ -234,14 +275,14 @@ public class UAVObjectField { List l = (List) data; Byte val = l.get(index); - if(val >= options.size() || val < 0) - throw new Exception("Invalid value for" + name); + //if(val >= options.size() || val < 0) + // throw new Exception("Invalid value for" + name); return options.get(val); } case STRING: { - throw new Exception("Shit I should do this"); + //throw new Exception("Shit I should do this"); } } // If this point is reached then we got an invalid type @@ -252,12 +293,9 @@ public class UAVObjectField { public void setValue(Object data, int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds - if ( index >= numElements ) + if ( index >= numElements ); //throw new Exception("Index out of bounds"); - System.out.println(data.toString()); - System.out.println(this.data.toString()); - // Get metadata UAVObject.Metadata mdata = obj.getMetadata(); // Update value if the access mode permits @@ -266,23 +304,19 @@ public class UAVObjectField { switch (type) { case INT8: - data = new Integer((Byte) data); case INT16: - data = new Integer((Short) data); case INT32: { List l = (List) this.data; - l.set(index,(Integer) data); + l.set(index,((Number) data).intValue()); break; } case UINT8: - data = new Integer((Byte) data); case UINT16: - data = new Integer((Short) data); case UINT32: { List l = (List) this.data; - l.set(index, (Integer) data); + l.set(index,((Number) data).intValue()); break; } case FLOAT32: @@ -386,7 +420,7 @@ public class UAVObjectField { sout += name + ": [ "; for (int n = 0; n < numElements; ++n) { - sout += String.valueOf(n) + " "; + sout += String.valueOf(n) + "(" + getValue(n) + ") "; } sout += "] " + units + "\n"; @@ -442,9 +476,8 @@ public class UAVObjectField { this.data = null; this.obj = null; this.elementNames = elementNames; - // Set field size - System.out.println("Initializing: type " + type + this.numElements); + // Set field size switch (type) { case INT8: @@ -487,7 +520,6 @@ public class UAVObjectField { numBytesPerElement = 0; } clear(); - System.out.println("Initialized: " + this.data.toString()); } From cc7eb0f261ceae8ac1654e6a3fcba582f432addc Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 02:26:09 -0600 Subject: [PATCH 203/543] Make object store with the minimal amount of space and deal with unsigned values --- .../src/org/openpilot/uavtalk/UAVObject.java | 4 +- .../org/openpilot/uavtalk/UAVObjectField.java | 203 +++++++++++++----- .../java/uavobjectgeneratorjava.cpp | 4 +- 3 files changed, 148 insertions(+), 63 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index fe478cf2e..bf2c87d7e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -462,9 +462,7 @@ public abstract class UAVObject { * Return a string with the object information (only the header) */ public String toStringBrief() { - return getName() + " ( " + getObjID() + " " + getInstID() + " " + getNumBytes() + ")\n"; - // getName(), getObjID(), getInstID(), getNumBytes(), - // isSingleInstance()); + return getName() + " ( " + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index a9006e02f..78ebd7b52 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -27,8 +27,7 @@ public class UAVObjectField { public void initialize(UAVObject obj){ this.obj = obj; - clear(); - + //clear(); } public UAVObject getObject() { @@ -161,19 +160,19 @@ public class UAVObjectField { { case INT8: { - List l = (List) this.data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Byte val = dataIn.get(); - l.set(index, val.intValue()); + Long val = bound(dataIn.get()); + l.set(index, val.byteValue()); } break; } case INT16: { - List l = (List) this.data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Short val = dataIn.getShort(); - l.set(index, val.intValue()); + Long val = bound(dataIn.getShort()); + l.set(index, val.shortValue()); } break; } @@ -181,18 +180,18 @@ public class UAVObjectField { { List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Integer val = dataIn.getInt(); + Long val = bound(dataIn.getInt()); l.set(index, val.intValue()); } break; } case UINT8: - // TOOD: Deal with unsigned { - List l = (List) this.data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Byte val = dataIn.get(); - l.set(index, val.intValue()); + int signedval = (int) dataIn.get(); // this sign extends it + int unsignedval = signedval & 0xff; // drop sign extension + l.set(index, (short) unsignedval); } break; } @@ -200,17 +199,19 @@ public class UAVObjectField { { List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Short val = dataIn.getShort(); - l.set(index, val.intValue()); + int signedval = (int) dataIn.getShort(); // this sign extends it + int unsignedval = signedval & 0xffff; // drop sign extension + l.set(index, unsignedval); } break; } case UINT32: { - List l = (List) this.data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - Integer val = dataIn.getInt(); - l.set(index, val.intValue()); + long signedval = (long) dataIn.getInt(); // this sign extends it + long unsignedval = signedval & 0xffffffffL; // drop sign extension + l.set(index, unsignedval); } break; } @@ -240,36 +241,31 @@ public class UAVObjectField { } Object getValue() { return getValue(0); }; - Object getValue(int index) { + @SuppressWarnings("unchecked") + Object getValue(int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds if ( index >= numElements ) { return null; } - + switch (type) { case INT8: + return ((List) data).get(index).intValue(); case INT16: + return ((List) data).get(index).intValue(); case INT32: - { - List l = (List) data; - return l.get(index); - } + return ((List) data).get(index).intValue(); case UINT8: + return ((List) data).get(index).intValue(); case UINT16: + return ((List) data).get(index).intValue(); case UINT32: - { - // TODO: Correctly deal with unsigned values - List l = (List) data; - return l.get(index); - } + return ((List) data).get(index); case FLOAT32: - { - List l = (List) data; - return l.get(index); - } + return ((List) data).get(index); case ENUM: { List l = (List) data; @@ -290,10 +286,11 @@ public class UAVObjectField { } public void setValue(Object data) { setValue(data,0); } - public void setValue(Object data, int index) { + @SuppressWarnings("unchecked") + public void setValue(Object data, int index) { // QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds - if ( index >= numElements ); + //if ( index >= numElements ); //throw new Exception("Index out of bounds"); // Get metadata @@ -304,25 +301,45 @@ public class UAVObjectField { switch (type) { case INT8: + { + List l = (List) this.data; + l.set(index, bound(data).byteValue()); + break; + } case INT16: + { + List l = (List) this.data; + l.set(index, bound(data).shortValue()); + break; + } case INT32: { List l = (List) this.data; - l.set(index,((Number) data).intValue()); + l.set(index, bound(data).intValue()); break; } case UINT8: + { + List l = (List) this.data; + l.set(index, bound(data).shortValue()); + break; + } case UINT16: - case UINT32: { List l = (List) this.data; - l.set(index,((Number) data).intValue()); + l.set(index, bound(data).intValue()); + break; + } + case UINT32: + { + List l = (List) this.data; + l.set(index, bound(data)); break; } case FLOAT32: { List l = (List) this.data; - l.set(index, (Float) data); + l.set(index, ((Number) data).floatValue()); break; } case ENUM: @@ -431,37 +448,46 @@ public class UAVObjectField { } - public void clear() { + @SuppressWarnings("unchecked") + public void clear() { switch (type) { case INT8: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((byte) 0); + } + break; case INT16: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((short) 0); + } + break; case INT32: - case UINT8: - case UINT16: - case UINT32: ((ArrayList) data).clear(); for(int index = 0; index < numElements; ++index) { ((ArrayList) data).add(0); } break; - case FLOAT32: - ((ArrayList) data).clear(); + case UINT8: + ((ArrayList) data).clear(); for(int index = 0; index < numElements; ++index) { - ((ArrayList) data).add((float) 0); + ((ArrayList) data).add((short) 0); } break; - case ENUM: - ((ArrayList) data).clear(); + case UINT16: + ((ArrayList) data).clear(); for(int index = 0; index < numElements; ++index) { - ((ArrayList) data).add((byte)0); + ((ArrayList) data).add(0); } break; - case STRING: - // TODO: Add string + case UINT32: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((long) 0); + } break; - default: - numBytesPerElement = 0; } } @@ -481,11 +507,11 @@ public class UAVObjectField { switch (type) { case INT8: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case INT16: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 2; break; case INT32: @@ -493,7 +519,7 @@ public class UAVObjectField { numBytesPerElement = 4; break; case UINT8: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; case UINT16: @@ -501,11 +527,11 @@ public class UAVObjectField { numBytesPerElement = 2; break; case UINT32: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case FLOAT32: - data = (Object) new ArrayList(this.numElements); + data = (Object) new ArrayList(this.numElements); numBytesPerElement = 4; break; case ENUM: @@ -520,8 +546,69 @@ public class UAVObjectField { numBytesPerElement = 0; } clear(); + + System.out.println(this); } + /** + * For numerical types bounds the data appropriately + * @param val Can be any object, for numerical tries to cast to Number + * @return long value with the right range (for float rounds) + * @note This is mostly needed because java has no unsigned integer + */ + protected Long bound (Object val) { + + switch(type) { + case ENUM: + case STRING: + return 0L; + case FLOAT32: + return ((Number) val).longValue(); + } + + long num = ((Number) val).longValue(); + + switch(type) { + case INT8: + if(num < Byte.MIN_VALUE) + return (long) Byte.MAX_VALUE; + if(num > Byte.MAX_VALUE) + return (long) Byte.MAX_VALUE; + return num; + case INT16: + if(num < Short.MIN_VALUE) + return (long) Short.MIN_VALUE; + if(num > Short.MAX_VALUE) + return (long) Short.MAX_VALUE; + return num; + case INT32: + if(num < Integer.MIN_VALUE) + return (long) Integer.MIN_VALUE; + if(num > Integer.MAX_VALUE) + return (long) Integer.MAX_VALUE; + return num; + case UINT8: + if(num < 0) + return (long) 0; + if(num > 255) + return (long) 255; + return num; + case UINT16: + if(num < 0) + return (long) 0; + if(num > 65535) + return (long) 65535; + return num; + case UINT32: + if(num < 0) + return (long) 0; + if(num > 4294967295L) + return 4294967295L; + return num; + } + + return num; + } private String name; private String units; diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index ce436e6af..7319b7767 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -29,8 +29,8 @@ using namespace std; bool UAVObjectGeneratorJava::generate(UAVObjectParser* parser,QString templatepath,QString outputpath) { - fieldTypeStrCPP << "qint8" << "qint16" << "qint32" << - "quint8" << "quint16" << "quint32" << "float" << "quint8"; + fieldTypeStrCPP << "Byte" << "Short" << "Int" << + "Short" << "Int" << "Long" << "Float" << "Byte"; fieldTypeStrCPPClass << "INT8" << "INT16" << "INT32" << "UINT8" << "UINT16" << "UINT32" << "FLOAT32" << "ENUM"; From 75118e0abc0afb404fb1588e65734d8dac6f083f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:10:48 -0600 Subject: [PATCH 204/543] Added unit tests --- .../org/openpilot/uavtalk/FieldTest.java | 121 ++++++++++++++++++ .../org/openpilot/uavtalk/SettingsTest.java | 34 +++++ 2 files changed, 155 insertions(+) create mode 100644 androidgcs/tests/org/openpilot/uavtalk/FieldTest.java create mode 100644 androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java diff --git a/androidgcs/tests/org/openpilot/uavtalk/FieldTest.java b/androidgcs/tests/org/openpilot/uavtalk/FieldTest.java new file mode 100644 index 000000000..2d161fc25 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/FieldTest.java @@ -0,0 +1,121 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; + +import org.junit.BeforeClass; +import org.junit.Test; + +import org.openpilot.uavtalk.UAVObjectField; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.uavobjects.*; + +public class FieldTest { + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + } + + @Test + public void testPackUint16() { + // Need an object initialized to the field to provide metadata + UAVObject obj = null; + try { + obj = new ActuatorCommand(); + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.UINT16, 3, null); + field.initialize(obj); + field.setValue(3,0); + field.setValue(-50,1); + field.setValue(5003585,2); + + ByteBuffer bbuf = ByteBuffer.allocate(field.getNumBytes()); + + try { + field.pack(bbuf); + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + fail("Buffer size incorrect"); + } + + // Expect data to come out as little endian + byte[] expected = {3,0,0,0,(byte) 0xff,(byte) 0xff}; + for(int i = 0; i < expected.length && i < bbuf.array().length; i++) { + System.out.println("Expected: " + expected[i] + " (" + i + ")"); + System.out.println("Received: " + bbuf.array()[i] + " (" + i + ")"); + assertEquals(bbuf.array()[i],expected[i]); + } + } + + @Test + public void testUnpackUint16() { + // Need an object initialized to the field to provide metadata + UAVObject obj = null; + obj = new ActuatorCommand(); + UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.UINT16, 3, null); + field.initialize(obj); + + ByteBuffer bbuf = ByteBuffer.allocate(field.getNumBytes()); + byte[] expected = {3,0,0,0,(byte) 0xff,(byte) 0xff}; + bbuf.put(expected); + bbuf.position(0); + field.unpack(bbuf); + + assertEquals(field.getValue(0), 3); + assertEquals(field.getValue(1), 0); + assertEquals(field.getValue(2), 65535); + } + + @Test + public void testEnumSetGetValue() { + List options = new ArrayList(); + options.add("Opt1"); + options.add("Opt2"); + options.add("Opt3"); + + // Need an object initialized to the field to provide metadata + UAVObject obj = null; + try { + obj = new ActuatorCommand(); + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.ENUM, 3, options); + field.initialize(obj); + field.setValue("Opt1",0); + field.setValue("Opt2",1); + field.setValue("Opt3",2); + assertEquals(field.getValue(0), "Opt1"); + assertEquals(field.getValue(1), "Opt2"); + assertEquals(field.getValue(2), "Opt3"); + } + + @Test + public void testUint16SetGetValue() { + + // Need an object initialized to the field to provide metadata + UAVObject obj = null; + try { + obj = new ActuatorCommand(); + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.UINT16, 3, null); + field.initialize(obj); + field.setValue(3,0); + field.setValue(-50,1); + field.setValue(5003585,2); + assertEquals(field.getValue(0), 3); + assertEquals(field.getValue(1), 0); + assertEquals(field.getValue(2), 65535); + } +} diff --git a/androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java b/androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java new file mode 100644 index 000000000..5a805ae88 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java @@ -0,0 +1,34 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import org.junit.BeforeClass; +import org.junit.Test; + +public class SettingsTest { + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + } + + @Test + public void testGetDefaultMetadata() { + fail("Not yet implemented"); + } + + @Test + public void testSetDefaultFieldValues() { + fail("Not yet implemented"); + } + + @Test + public void testIsSettings() { + fail("Not yet implemented"); + } + + @Test + public void testGetField() { + fail("Not yet implemented"); + } + +} From 22e00c780f02ba922b4ba87658d3785a63e26377 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:11:07 -0600 Subject: [PATCH 205/543] More updates to the java objects. Also checking in the auto generated code for now to make things easier. --- .../uavtalk/uavobjects/AHRSCalibration.java | 243 ++++++++++ .../uavtalk/uavobjects/AHRSSettings.java | 178 +++++++ .../uavtalk/uavobjects/ActuatorCommand.java | 158 ++++++ .../uavtalk/uavobjects/ActuatorDesired.java | 159 ++++++ .../uavtalk/uavobjects/ActuatorSettings.java | 455 ++++++++++++++++++ .../uavtalk/uavobjects/AhrsStatus.java | 201 ++++++++ .../uavtalk/uavobjects/AttitudeActual.java | 163 +++++++ .../uavtalk/uavobjects/AttitudeRaw.java | 158 ++++++ .../uavtalk/uavobjects/AttitudeSettings.java | 159 ++++++ .../uavtalk/uavobjects/BaroAltitude.java | 147 ++++++ .../uavtalk/uavobjects/BatterySettings.java | 163 +++++++ .../uavtalk/uavobjects/FirmwareIAPObj.java | 258 ++++++++++ .../uavobjects/FlightBatteryState.java | 165 +++++++ .../uavtalk/uavobjects/FlightPlanControl.java | 144 ++++++ .../uavobjects/FlightPlanSettings.java | 140 ++++++ .../uavtalk/uavobjects/FlightPlanStatus.java | 187 +++++++ .../uavobjects/FlightTelemetryStats.java | 164 +++++++ .../uavtalk/uavobjects/GCSTelemetryStats.java | 164 +++++++ .../uavtalk/uavobjects/GPSPosition.java | 184 +++++++ .../uavtalk/uavobjects/GPSSatellites.java | 215 +++++++++ .../openpilot/uavtalk/uavobjects/GPSTime.java | 159 ++++++ .../uavtalk/uavobjects/GuidanceSettings.java | 197 ++++++++ .../uavtalk/uavobjects/HomeLocation.java | 197 ++++++++ .../uavtalk/uavobjects/I2CStats.java | 238 +++++++++ .../uavobjects/ManualControlCommand.java | 199 ++++++++ .../uavobjects/ManualControlSettings.java | 395 +++++++++++++++ .../uavtalk/uavobjects/MixerSettings.java | 357 ++++++++++++++ .../uavtalk/uavobjects/MixerStatus.java | 167 +++++++ .../uavtalk/uavobjects/NedAccel.java | 147 ++++++ .../uavtalk/uavobjects/ObjectPersistence.java | 160 ++++++ .../uavtalk/uavobjects/PositionActual.java | 147 ++++++ .../uavtalk/uavobjects/PositionDesired.java | 147 ++++++ .../uavtalk/uavobjects/RateDesired.java | 147 ++++++ .../uavtalk/uavobjects/SonarAltitude.java | 139 ++++++ .../uavobjects/StabilizationDesired.java | 161 +++++++ .../uavobjects/StabilizationSettings.java | 222 +++++++++ .../uavtalk/uavobjects/SystemAlarms.java | 176 +++++++ .../uavtalk/uavobjects/SystemSettings.java | 157 ++++++ .../uavtalk/uavobjects/SystemStats.java | 151 ++++++ .../uavtalk/uavobjects/TaskInfo.java | 170 +++++++ .../uavtalk/uavobjects/TelemetrySettings.java | 148 ++++++ .../uavobjects/UAVObjectsInitialize.java | 87 ++++ .../uavtalk/uavobjects/VelocityActual.java | 147 ++++++ .../uavtalk/uavobjects/VelocityDesired.java | 147 ++++++ .../uavtalk/uavobjects/WatchdogStatus.java | 143 ++++++ 45 files changed, 8310 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java new file mode 100644 index 000000000..a3096ad39 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java @@ -0,0 +1,243 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the calibration settings for the @ref AHRSCommsModule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the calibration settings for the @ref AHRSCommsModule + +generated from ahrscalibration.xml + **/ +public class AHRSCalibration extends UAVDataObject { + + public AHRSCalibration() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List measure_varElemNames = new ArrayList(); + measure_varElemNames.add("0"); + List measure_varEnumOptions = new ArrayList(); + measure_varEnumOptions.add("SET"); + measure_varEnumOptions.add("MEASURE"); + fields.add( new UAVObjectField("measure_var", "", UAVObjectField.FieldType.ENUM, measure_varElemNames, measure_varEnumOptions) ); + + List accel_biasElemNames = new ArrayList(); + accel_biasElemNames.add("X"); + accel_biasElemNames.add("Y"); + accel_biasElemNames.add("Z"); + fields.add( new UAVObjectField("accel_bias", "m/s^2", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); + + List accel_scaleElemNames = new ArrayList(); + accel_scaleElemNames.add("X"); + accel_scaleElemNames.add("Y"); + accel_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("accel_scale", "(m/s^2)/lsb", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); + + List accel_varElemNames = new ArrayList(); + accel_varElemNames.add("X"); + accel_varElemNames.add("Y"); + accel_varElemNames.add("Z"); + fields.add( new UAVObjectField("accel_var", "(m/s^2)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); + + List gyro_biasElemNames = new ArrayList(); + gyro_biasElemNames.add("X"); + gyro_biasElemNames.add("Y"); + gyro_biasElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_bias", "rad/s", UAVObjectField.FieldType.FLOAT32, gyro_biasElemNames, null) ); + + List gyro_scaleElemNames = new ArrayList(); + gyro_scaleElemNames.add("X"); + gyro_scaleElemNames.add("Y"); + gyro_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_scale", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, gyro_scaleElemNames, null) ); + + List gyro_varElemNames = new ArrayList(); + gyro_varElemNames.add("X"); + gyro_varElemNames.add("Y"); + gyro_varElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_var", "(rad/s)^2", UAVObjectField.FieldType.FLOAT32, gyro_varElemNames, null) ); + + List gyro_tempcompfactorElemNames = new ArrayList(); + gyro_tempcompfactorElemNames.add("X"); + gyro_tempcompfactorElemNames.add("Y"); + gyro_tempcompfactorElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_tempcompfactor", "raw/raw", UAVObjectField.FieldType.FLOAT32, gyro_tempcompfactorElemNames, null) ); + + List mag_biasElemNames = new ArrayList(); + mag_biasElemNames.add("X"); + mag_biasElemNames.add("Y"); + mag_biasElemNames.add("Z"); + fields.add( new UAVObjectField("mag_bias", "mGau", UAVObjectField.FieldType.FLOAT32, mag_biasElemNames, null) ); + + List mag_scaleElemNames = new ArrayList(); + mag_scaleElemNames.add("X"); + mag_scaleElemNames.add("Y"); + mag_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("mag_scale", "(mGau)/lsb", UAVObjectField.FieldType.FLOAT32, mag_scaleElemNames, null) ); + + List mag_varElemNames = new ArrayList(); + mag_varElemNames.add("X"); + mag_varElemNames.add("Y"); + mag_varElemNames.add("Z"); + fields.add( new UAVObjectField("mag_var", "mGau^2", UAVObjectField.FieldType.FLOAT32, mag_varElemNames, null) ); + + List vel_varElemNames = new ArrayList(); + vel_varElemNames.add("0"); + fields.add( new UAVObjectField("vel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, vel_varElemNames, null) ); + + List pos_varElemNames = new ArrayList(); + pos_varElemNames.add("0"); + fields.add( new UAVObjectField("pos_var", "m^2", UAVObjectField.FieldType.FLOAT32, pos_varElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("measure_var").setValue(0); + getField("accel_bias").setValue(-73.5,0); + getField("accel_bias").setValue(-73.5,1); + getField("accel_bias").setValue(73.5,2); + getField("accel_scale").setValue(0.0359,0); + getField("accel_scale").setValue(0.0359,1); + getField("accel_scale").setValue(-0.0359,2); + getField("accel_var").setValue(0.0005,0); + getField("accel_var").setValue(0.0005,1); + getField("accel_var").setValue(0.0005,2); + getField("gyro_bias").setValue(23,0); + getField("gyro_bias").setValue(-23,1); + getField("gyro_bias").setValue(23,2); + getField("gyro_scale").setValue(-0.017,0); + getField("gyro_scale").setValue(0.017,1); + getField("gyro_scale").setValue(-0.017,2); + getField("gyro_var").setValue(0.0001,0); + getField("gyro_var").setValue(0.0001,1); + getField("gyro_var").setValue(0.0001,2); + getField("gyro_tempcompfactor").setValue(0,0); + getField("gyro_tempcompfactor").setValue(0,1); + getField("gyro_tempcompfactor").setValue(0,2); + getField("mag_bias").setValue(0,0); + getField("mag_bias").setValue(0,1); + getField("mag_bias").setValue(0,2); + getField("mag_scale").setValue(-2,0); + getField("mag_scale").setValue(-2,1); + getField("mag_scale").setValue(-2,2); + getField("mag_var").setValue(50,0); + getField("mag_var").setValue(50,1); + getField("mag_var").setValue(50,2); + getField("vel_var").setValue(0.4); + getField("pos_var").setValue(0.4); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AHRSCalibration obj = new AHRSCalibration(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AHRSCalibration GetInstance(UAVObjectManager objMngr, int instID) + { + return (AHRSCalibration)(objMngr.getObject(AHRSCalibration.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x30101BB2; + protected static final String NAME = "AHRSCalibration"; + protected static String DESCRIPTION = "Contains the calibration settings for the @ref AHRSCommsModule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java new file mode 100644 index 000000000..a38915c28 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java @@ -0,0 +1,178 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref AHRSCommsModule to control the algorithm and what is updated + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref AHRSCommsModule to control the algorithm and what is updated + +generated from ahrssettings.xml + **/ +public class AHRSSettings extends UAVDataObject { + + public AHRSSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AlgorithmElemNames = new ArrayList(); + AlgorithmElemNames.add("0"); + List AlgorithmEnumOptions = new ArrayList(); + AlgorithmEnumOptions.add("SIMPLE"); + AlgorithmEnumOptions.add("INSGPS_INDOOR_NOMAG"); + AlgorithmEnumOptions.add("INSGPS_INDOOR"); + AlgorithmEnumOptions.add("INSGPS_OUTDOOR"); + fields.add( new UAVObjectField("Algorithm", "", UAVObjectField.FieldType.ENUM, AlgorithmElemNames, AlgorithmEnumOptions) ); + + List DownsamplingElemNames = new ArrayList(); + DownsamplingElemNames.add("0"); + fields.add( new UAVObjectField("Downsampling", "", UAVObjectField.FieldType.UINT8, DownsamplingElemNames, null) ); + + List UpdatePeriodElemNames = new ArrayList(); + UpdatePeriodElemNames.add("0"); + fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.UINT8, UpdatePeriodElemNames, null) ); + + List BiasCorrectedRawElemNames = new ArrayList(); + BiasCorrectedRawElemNames.add("0"); + List BiasCorrectedRawEnumOptions = new ArrayList(); + BiasCorrectedRawEnumOptions.add("TRUE"); + BiasCorrectedRawEnumOptions.add("FALSE"); + fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); + + List YawBiasElemNames = new ArrayList(); + YawBiasElemNames.add("0"); + fields.add( new UAVObjectField("YawBias", "", UAVObjectField.FieldType.FLOAT32, YawBiasElemNames, null) ); + + List PitchBiasElemNames = new ArrayList(); + PitchBiasElemNames.add("0"); + fields.add( new UAVObjectField("PitchBias", "", UAVObjectField.FieldType.FLOAT32, PitchBiasElemNames, null) ); + + List RollBiasElemNames = new ArrayList(); + RollBiasElemNames.add("0"); + fields.add( new UAVObjectField("RollBias", "", UAVObjectField.FieldType.FLOAT32, RollBiasElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Algorithm").setValue(1); + getField("Downsampling").setValue(20); + getField("UpdatePeriod").setValue(1); + getField("BiasCorrectedRaw").setValue(0); + getField("YawBias").setValue(0); + getField("PitchBias").setValue(0); + getField("RollBias").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AHRSSettings obj = new AHRSSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AHRSSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (AHRSSettings)(objMngr.getObject(AHRSSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xDEFC5548; + protected static final String NAME = "AHRSSettings"; + protected static String DESCRIPTION = "Settings for the @ref AHRSCommsModule to control the algorithm and what is updated"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java new file mode 100644 index 000000000..a5d6230ac --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java @@ -0,0 +1,158 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule + +generated from actuatorcommand.xml + **/ +public class ActuatorCommand extends UAVDataObject { + + public ActuatorCommand() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ChannelElemNames = new ArrayList(); + ChannelElemNames.add("0"); + ChannelElemNames.add("1"); + ChannelElemNames.add("2"); + ChannelElemNames.add("3"); + ChannelElemNames.add("4"); + ChannelElemNames.add("5"); + ChannelElemNames.add("6"); + ChannelElemNames.add("7"); + fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.INT16, ChannelElemNames, null) ); + + List UpdateTimeElemNames = new ArrayList(); + UpdateTimeElemNames.add("0"); + fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.UINT8, UpdateTimeElemNames, null) ); + + List MaxUpdateTimeElemNames = new ArrayList(); + MaxUpdateTimeElemNames.add("0"); + fields.add( new UAVObjectField("MaxUpdateTime", "ms", UAVObjectField.FieldType.UINT16, MaxUpdateTimeElemNames, null) ); + + List NumFailedUpdatesElemNames = new ArrayList(); + NumFailedUpdatesElemNames.add("0"); + fields.add( new UAVObjectField("NumFailedUpdates", "", UAVObjectField.FieldType.UINT8, NumFailedUpdatesElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ActuatorCommand obj = new ActuatorCommand(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ActuatorCommand GetInstance(UAVObjectManager objMngr, int instID) + { + return (ActuatorCommand)(objMngr.getObject(ActuatorCommand.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE8E077D8; + protected static final String NAME = "ActuatorCommand"; + protected static String DESCRIPTION = "Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java new file mode 100644 index 000000000..b81ca29da --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode. + +generated from actuatordesired.xml + **/ +public class ActuatorDesired extends UAVDataObject { + + public ActuatorDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "%", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "%", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "%", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); + + List UpdateTimeElemNames = new ArrayList(); + UpdateTimeElemNames.add("0"); + fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.FLOAT32, UpdateTimeElemNames, null) ); + + List NumLongUpdatesElemNames = new ArrayList(); + NumLongUpdatesElemNames.add("0"); + fields.add( new UAVObjectField("NumLongUpdates", "ms", UAVObjectField.FieldType.FLOAT32, NumLongUpdatesElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ActuatorDesired obj = new ActuatorDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ActuatorDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (ActuatorDesired)(objMngr.getObject(ActuatorDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD4516782; + protected static final String NAME = "ActuatorDesired"; + protected static String DESCRIPTION = "Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java new file mode 100644 index 000000000..ebbfaeb17 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java @@ -0,0 +1,455 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + +generated from actuatorsettings.xml + **/ +public class ActuatorSettings extends UAVDataObject { + + public ActuatorSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List FixedWingRoll1ElemNames = new ArrayList(); + FixedWingRoll1ElemNames.add("0"); + List FixedWingRoll1EnumOptions = new ArrayList(); + FixedWingRoll1EnumOptions.add("Channel1"); + FixedWingRoll1EnumOptions.add("Channel2"); + FixedWingRoll1EnumOptions.add("Channel3"); + FixedWingRoll1EnumOptions.add("Channel4"); + FixedWingRoll1EnumOptions.add("Channel5"); + FixedWingRoll1EnumOptions.add("Channel6"); + FixedWingRoll1EnumOptions.add("Channel7"); + FixedWingRoll1EnumOptions.add("Channel8"); + FixedWingRoll1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingRoll1", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll1ElemNames, FixedWingRoll1EnumOptions) ); + + List FixedWingRoll2ElemNames = new ArrayList(); + FixedWingRoll2ElemNames.add("0"); + List FixedWingRoll2EnumOptions = new ArrayList(); + FixedWingRoll2EnumOptions.add("Channel1"); + FixedWingRoll2EnumOptions.add("Channel2"); + FixedWingRoll2EnumOptions.add("Channel3"); + FixedWingRoll2EnumOptions.add("Channel4"); + FixedWingRoll2EnumOptions.add("Channel5"); + FixedWingRoll2EnumOptions.add("Channel6"); + FixedWingRoll2EnumOptions.add("Channel7"); + FixedWingRoll2EnumOptions.add("Channel8"); + FixedWingRoll2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingRoll2", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll2ElemNames, FixedWingRoll2EnumOptions) ); + + List FixedWingPitch1ElemNames = new ArrayList(); + FixedWingPitch1ElemNames.add("0"); + List FixedWingPitch1EnumOptions = new ArrayList(); + FixedWingPitch1EnumOptions.add("Channel1"); + FixedWingPitch1EnumOptions.add("Channel2"); + FixedWingPitch1EnumOptions.add("Channel3"); + FixedWingPitch1EnumOptions.add("Channel4"); + FixedWingPitch1EnumOptions.add("Channel5"); + FixedWingPitch1EnumOptions.add("Channel6"); + FixedWingPitch1EnumOptions.add("Channel7"); + FixedWingPitch1EnumOptions.add("Channel8"); + FixedWingPitch1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingPitch1", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch1ElemNames, FixedWingPitch1EnumOptions) ); + + List FixedWingPitch2ElemNames = new ArrayList(); + FixedWingPitch2ElemNames.add("0"); + List FixedWingPitch2EnumOptions = new ArrayList(); + FixedWingPitch2EnumOptions.add("Channel1"); + FixedWingPitch2EnumOptions.add("Channel2"); + FixedWingPitch2EnumOptions.add("Channel3"); + FixedWingPitch2EnumOptions.add("Channel4"); + FixedWingPitch2EnumOptions.add("Channel5"); + FixedWingPitch2EnumOptions.add("Channel6"); + FixedWingPitch2EnumOptions.add("Channel7"); + FixedWingPitch2EnumOptions.add("Channel8"); + FixedWingPitch2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingPitch2", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch2ElemNames, FixedWingPitch2EnumOptions) ); + + List FixedWingYawElemNames = new ArrayList(); + FixedWingYawElemNames.add("0"); + List FixedWingYawEnumOptions = new ArrayList(); + FixedWingYawEnumOptions.add("Channel1"); + FixedWingYawEnumOptions.add("Channel2"); + FixedWingYawEnumOptions.add("Channel3"); + FixedWingYawEnumOptions.add("Channel4"); + FixedWingYawEnumOptions.add("Channel5"); + FixedWingYawEnumOptions.add("Channel6"); + FixedWingYawEnumOptions.add("Channel7"); + FixedWingYawEnumOptions.add("Channel8"); + FixedWingYawEnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingYaw", "channel", UAVObjectField.FieldType.ENUM, FixedWingYawElemNames, FixedWingYawEnumOptions) ); + + List FixedWingThrottleElemNames = new ArrayList(); + FixedWingThrottleElemNames.add("0"); + List FixedWingThrottleEnumOptions = new ArrayList(); + FixedWingThrottleEnumOptions.add("Channel1"); + FixedWingThrottleEnumOptions.add("Channel2"); + FixedWingThrottleEnumOptions.add("Channel3"); + FixedWingThrottleEnumOptions.add("Channel4"); + FixedWingThrottleEnumOptions.add("Channel5"); + FixedWingThrottleEnumOptions.add("Channel6"); + FixedWingThrottleEnumOptions.add("Channel7"); + FixedWingThrottleEnumOptions.add("Channel8"); + FixedWingThrottleEnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingThrottle", "channel", UAVObjectField.FieldType.ENUM, FixedWingThrottleElemNames, FixedWingThrottleEnumOptions) ); + + List VTOLMotorNElemNames = new ArrayList(); + VTOLMotorNElemNames.add("0"); + List VTOLMotorNEnumOptions = new ArrayList(); + VTOLMotorNEnumOptions.add("Channel1"); + VTOLMotorNEnumOptions.add("Channel2"); + VTOLMotorNEnumOptions.add("Channel3"); + VTOLMotorNEnumOptions.add("Channel4"); + VTOLMotorNEnumOptions.add("Channel5"); + VTOLMotorNEnumOptions.add("Channel6"); + VTOLMotorNEnumOptions.add("Channel7"); + VTOLMotorNEnumOptions.add("Channel8"); + VTOLMotorNEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorN", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNElemNames, VTOLMotorNEnumOptions) ); + + List VTOLMotorNEElemNames = new ArrayList(); + VTOLMotorNEElemNames.add("0"); + List VTOLMotorNEEnumOptions = new ArrayList(); + VTOLMotorNEEnumOptions.add("Channel1"); + VTOLMotorNEEnumOptions.add("Channel2"); + VTOLMotorNEEnumOptions.add("Channel3"); + VTOLMotorNEEnumOptions.add("Channel4"); + VTOLMotorNEEnumOptions.add("Channel5"); + VTOLMotorNEEnumOptions.add("Channel6"); + VTOLMotorNEEnumOptions.add("Channel7"); + VTOLMotorNEEnumOptions.add("Channel8"); + VTOLMotorNEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorNE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNEElemNames, VTOLMotorNEEnumOptions) ); + + List VTOLMotorEElemNames = new ArrayList(); + VTOLMotorEElemNames.add("0"); + List VTOLMotorEEnumOptions = new ArrayList(); + VTOLMotorEEnumOptions.add("Channel1"); + VTOLMotorEEnumOptions.add("Channel2"); + VTOLMotorEEnumOptions.add("Channel3"); + VTOLMotorEEnumOptions.add("Channel4"); + VTOLMotorEEnumOptions.add("Channel5"); + VTOLMotorEEnumOptions.add("Channel6"); + VTOLMotorEEnumOptions.add("Channel7"); + VTOLMotorEEnumOptions.add("Channel8"); + VTOLMotorEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorEElemNames, VTOLMotorEEnumOptions) ); + + List VTOLMotorSEElemNames = new ArrayList(); + VTOLMotorSEElemNames.add("0"); + List VTOLMotorSEEnumOptions = new ArrayList(); + VTOLMotorSEEnumOptions.add("Channel1"); + VTOLMotorSEEnumOptions.add("Channel2"); + VTOLMotorSEEnumOptions.add("Channel3"); + VTOLMotorSEEnumOptions.add("Channel4"); + VTOLMotorSEEnumOptions.add("Channel5"); + VTOLMotorSEEnumOptions.add("Channel6"); + VTOLMotorSEEnumOptions.add("Channel7"); + VTOLMotorSEEnumOptions.add("Channel8"); + VTOLMotorSEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorSE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSEElemNames, VTOLMotorSEEnumOptions) ); + + List VTOLMotorSElemNames = new ArrayList(); + VTOLMotorSElemNames.add("0"); + List VTOLMotorSEnumOptions = new ArrayList(); + VTOLMotorSEnumOptions.add("Channel1"); + VTOLMotorSEnumOptions.add("Channel2"); + VTOLMotorSEnumOptions.add("Channel3"); + VTOLMotorSEnumOptions.add("Channel4"); + VTOLMotorSEnumOptions.add("Channel5"); + VTOLMotorSEnumOptions.add("Channel6"); + VTOLMotorSEnumOptions.add("Channel7"); + VTOLMotorSEnumOptions.add("Channel8"); + VTOLMotorSEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorS", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSElemNames, VTOLMotorSEnumOptions) ); + + List VTOLMotorSWElemNames = new ArrayList(); + VTOLMotorSWElemNames.add("0"); + List VTOLMotorSWEnumOptions = new ArrayList(); + VTOLMotorSWEnumOptions.add("Channel1"); + VTOLMotorSWEnumOptions.add("Channel2"); + VTOLMotorSWEnumOptions.add("Channel3"); + VTOLMotorSWEnumOptions.add("Channel4"); + VTOLMotorSWEnumOptions.add("Channel5"); + VTOLMotorSWEnumOptions.add("Channel6"); + VTOLMotorSWEnumOptions.add("Channel7"); + VTOLMotorSWEnumOptions.add("Channel8"); + VTOLMotorSWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorSW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSWElemNames, VTOLMotorSWEnumOptions) ); + + List VTOLMotorWElemNames = new ArrayList(); + VTOLMotorWElemNames.add("0"); + List VTOLMotorWEnumOptions = new ArrayList(); + VTOLMotorWEnumOptions.add("Channel1"); + VTOLMotorWEnumOptions.add("Channel2"); + VTOLMotorWEnumOptions.add("Channel3"); + VTOLMotorWEnumOptions.add("Channel4"); + VTOLMotorWEnumOptions.add("Channel5"); + VTOLMotorWEnumOptions.add("Channel6"); + VTOLMotorWEnumOptions.add("Channel7"); + VTOLMotorWEnumOptions.add("Channel8"); + VTOLMotorWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorWElemNames, VTOLMotorWEnumOptions) ); + + List VTOLMotorNWElemNames = new ArrayList(); + VTOLMotorNWElemNames.add("0"); + List VTOLMotorNWEnumOptions = new ArrayList(); + VTOLMotorNWEnumOptions.add("Channel1"); + VTOLMotorNWEnumOptions.add("Channel2"); + VTOLMotorNWEnumOptions.add("Channel3"); + VTOLMotorNWEnumOptions.add("Channel4"); + VTOLMotorNWEnumOptions.add("Channel5"); + VTOLMotorNWEnumOptions.add("Channel6"); + VTOLMotorNWEnumOptions.add("Channel7"); + VTOLMotorNWEnumOptions.add("Channel8"); + VTOLMotorNWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorNW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNWElemNames, VTOLMotorNWEnumOptions) ); + + List ChannelUpdateFreqElemNames = new ArrayList(); + ChannelUpdateFreqElemNames.add("0"); + ChannelUpdateFreqElemNames.add("1"); + ChannelUpdateFreqElemNames.add("2"); + ChannelUpdateFreqElemNames.add("3"); + fields.add( new UAVObjectField("ChannelUpdateFreq", "Hz", UAVObjectField.FieldType.UINT16, ChannelUpdateFreqElemNames, null) ); + + List ChannelMaxElemNames = new ArrayList(); + ChannelMaxElemNames.add("0"); + ChannelMaxElemNames.add("1"); + ChannelMaxElemNames.add("2"); + ChannelMaxElemNames.add("3"); + ChannelMaxElemNames.add("4"); + ChannelMaxElemNames.add("5"); + ChannelMaxElemNames.add("6"); + ChannelMaxElemNames.add("7"); + fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); + + List ChannelNeutralElemNames = new ArrayList(); + ChannelNeutralElemNames.add("0"); + ChannelNeutralElemNames.add("1"); + ChannelNeutralElemNames.add("2"); + ChannelNeutralElemNames.add("3"); + ChannelNeutralElemNames.add("4"); + ChannelNeutralElemNames.add("5"); + ChannelNeutralElemNames.add("6"); + ChannelNeutralElemNames.add("7"); + fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); + + List ChannelMinElemNames = new ArrayList(); + ChannelMinElemNames.add("0"); + ChannelMinElemNames.add("1"); + ChannelMinElemNames.add("2"); + ChannelMinElemNames.add("3"); + ChannelMinElemNames.add("4"); + ChannelMinElemNames.add("5"); + ChannelMinElemNames.add("6"); + ChannelMinElemNames.add("7"); + fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); + + List ChannelTypeElemNames = new ArrayList(); + ChannelTypeElemNames.add("0"); + ChannelTypeElemNames.add("1"); + ChannelTypeElemNames.add("2"); + ChannelTypeElemNames.add("3"); + ChannelTypeElemNames.add("4"); + ChannelTypeElemNames.add("5"); + ChannelTypeElemNames.add("6"); + ChannelTypeElemNames.add("7"); + List ChannelTypeEnumOptions = new ArrayList(); + ChannelTypeEnumOptions.add("PWM"); + ChannelTypeEnumOptions.add("MK"); + ChannelTypeEnumOptions.add("ASTEC4"); + fields.add( new UAVObjectField("ChannelType", "", UAVObjectField.FieldType.ENUM, ChannelTypeElemNames, ChannelTypeEnumOptions) ); + + List ChannelAddrElemNames = new ArrayList(); + ChannelAddrElemNames.add("0"); + ChannelAddrElemNames.add("1"); + ChannelAddrElemNames.add("2"); + ChannelAddrElemNames.add("3"); + ChannelAddrElemNames.add("4"); + ChannelAddrElemNames.add("5"); + ChannelAddrElemNames.add("6"); + ChannelAddrElemNames.add("7"); + fields.add( new UAVObjectField("ChannelAddr", "", UAVObjectField.FieldType.UINT8, ChannelAddrElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("FixedWingRoll1").setValue(8); + getField("FixedWingRoll2").setValue(8); + getField("FixedWingPitch1").setValue(8); + getField("FixedWingPitch2").setValue(8); + getField("FixedWingYaw").setValue(8); + getField("FixedWingThrottle").setValue(8); + getField("VTOLMotorN").setValue(8); + getField("VTOLMotorNE").setValue(8); + getField("VTOLMotorE").setValue(8); + getField("VTOLMotorSE").setValue(8); + getField("VTOLMotorS").setValue(8); + getField("VTOLMotorSW").setValue(8); + getField("VTOLMotorW").setValue(8); + getField("VTOLMotorNW").setValue(8); + getField("ChannelUpdateFreq").setValue(50,0); + getField("ChannelUpdateFreq").setValue(50,1); + getField("ChannelUpdateFreq").setValue(50,2); + getField("ChannelUpdateFreq").setValue(50,3); + getField("ChannelMax").setValue(1000,0); + getField("ChannelMax").setValue(1000,1); + getField("ChannelMax").setValue(1000,2); + getField("ChannelMax").setValue(1000,3); + getField("ChannelMax").setValue(1000,4); + getField("ChannelMax").setValue(1000,5); + getField("ChannelMax").setValue(1000,6); + getField("ChannelMax").setValue(1000,7); + getField("ChannelNeutral").setValue(1000,0); + getField("ChannelNeutral").setValue(1000,1); + getField("ChannelNeutral").setValue(1000,2); + getField("ChannelNeutral").setValue(1000,3); + getField("ChannelNeutral").setValue(1000,4); + getField("ChannelNeutral").setValue(1000,5); + getField("ChannelNeutral").setValue(1000,6); + getField("ChannelNeutral").setValue(1000,7); + getField("ChannelMin").setValue(1000,0); + getField("ChannelMin").setValue(1000,1); + getField("ChannelMin").setValue(1000,2); + getField("ChannelMin").setValue(1000,3); + getField("ChannelMin").setValue(1000,4); + getField("ChannelMin").setValue(1000,5); + getField("ChannelMin").setValue(1000,6); + getField("ChannelMin").setValue(1000,7); + getField("ChannelType").setValue(0,0); + getField("ChannelType").setValue(0,1); + getField("ChannelType").setValue(0,2); + getField("ChannelType").setValue(0,3); + getField("ChannelType").setValue(0,4); + getField("ChannelType").setValue(0,5); + getField("ChannelType").setValue(0,6); + getField("ChannelType").setValue(0,7); + getField("ChannelAddr").setValue(0,0); + getField("ChannelAddr").setValue(1,1); + getField("ChannelAddr").setValue(2,2); + getField("ChannelAddr").setValue(3,3); + getField("ChannelAddr").setValue(4,4); + getField("ChannelAddr").setValue(5,5); + getField("ChannelAddr").setValue(6,6); + getField("ChannelAddr").setValue(7,7); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ActuatorSettings obj = new ActuatorSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ActuatorSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (ActuatorSettings)(objMngr.getObject(ActuatorSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1BF864C2; + protected static final String NAME = "ActuatorSettings"; + protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java new file mode 100644 index 000000000..3ee8304ae --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java @@ -0,0 +1,201 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Status for the @ref AHRSCommsModule, including communication errors + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Status for the @ref AHRSCommsModule, including communication errors + +generated from ahrsstatus.xml + **/ +public class AhrsStatus extends UAVDataObject { + + public AhrsStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SerialNumberElemNames = new ArrayList(); + SerialNumberElemNames.add("0"); + SerialNumberElemNames.add("1"); + SerialNumberElemNames.add("2"); + SerialNumberElemNames.add("3"); + SerialNumberElemNames.add("4"); + SerialNumberElemNames.add("5"); + SerialNumberElemNames.add("6"); + SerialNumberElemNames.add("7"); + fields.add( new UAVObjectField("SerialNumber", "", UAVObjectField.FieldType.UINT8, SerialNumberElemNames, null) ); + + List CPULoadElemNames = new ArrayList(); + CPULoadElemNames.add("0"); + fields.add( new UAVObjectField("CPULoad", "count", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); + + List RunningTimeElemNames = new ArrayList(); + RunningTimeElemNames.add("0"); + fields.add( new UAVObjectField("RunningTime", "ms", UAVObjectField.FieldType.UINT32, RunningTimeElemNames, null) ); + + List IdleTimePerCyleElemNames = new ArrayList(); + IdleTimePerCyleElemNames.add("0"); + fields.add( new UAVObjectField("IdleTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, IdleTimePerCyleElemNames, null) ); + + List RunningTimePerCyleElemNames = new ArrayList(); + RunningTimePerCyleElemNames.add("0"); + fields.add( new UAVObjectField("RunningTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, RunningTimePerCyleElemNames, null) ); + + List DroppedUpdatesElemNames = new ArrayList(); + DroppedUpdatesElemNames.add("0"); + fields.add( new UAVObjectField("DroppedUpdates", "count", UAVObjectField.FieldType.UINT8, DroppedUpdatesElemNames, null) ); + + List LinkRunningElemNames = new ArrayList(); + LinkRunningElemNames.add("0"); + List LinkRunningEnumOptions = new ArrayList(); + LinkRunningEnumOptions.add("FALSE"); + LinkRunningEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("LinkRunning", "", UAVObjectField.FieldType.ENUM, LinkRunningElemNames, LinkRunningEnumOptions) ); + + List AhrsKickstartsElemNames = new ArrayList(); + AhrsKickstartsElemNames.add("0"); + fields.add( new UAVObjectField("AhrsKickstarts", "count", UAVObjectField.FieldType.UINT8, AhrsKickstartsElemNames, null) ); + + List AhrsCrcErrorsElemNames = new ArrayList(); + AhrsCrcErrorsElemNames.add("0"); + fields.add( new UAVObjectField("AhrsCrcErrors", "count", UAVObjectField.FieldType.UINT8, AhrsCrcErrorsElemNames, null) ); + + List AhrsRetriesElemNames = new ArrayList(); + AhrsRetriesElemNames.add("0"); + fields.add( new UAVObjectField("AhrsRetries", "count", UAVObjectField.FieldType.UINT8, AhrsRetriesElemNames, null) ); + + List AhrsInvalidPacketsElemNames = new ArrayList(); + AhrsInvalidPacketsElemNames.add("0"); + fields.add( new UAVObjectField("AhrsInvalidPackets", "count", UAVObjectField.FieldType.UINT8, AhrsInvalidPacketsElemNames, null) ); + + List OpCrcErrorsElemNames = new ArrayList(); + OpCrcErrorsElemNames.add("0"); + fields.add( new UAVObjectField("OpCrcErrors", "count", UAVObjectField.FieldType.UINT8, OpCrcErrorsElemNames, null) ); + + List OpRetriesElemNames = new ArrayList(); + OpRetriesElemNames.add("0"); + fields.add( new UAVObjectField("OpRetries", "count", UAVObjectField.FieldType.UINT8, OpRetriesElemNames, null) ); + + List OpInvalidPacketsElemNames = new ArrayList(); + OpInvalidPacketsElemNames.add("0"); + fields.add( new UAVObjectField("OpInvalidPackets", "count", UAVObjectField.FieldType.UINT8, OpInvalidPacketsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AhrsStatus obj = new AhrsStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AhrsStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (AhrsStatus)(objMngr.getObject(AhrsStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x37A5F7A2; + protected static final String NAME = "AhrsStatus"; + protected static String DESCRIPTION = "Status for the @ref AHRSCommsModule, including communication errors"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java new file mode 100644 index 000000000..714c18571 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java @@ -0,0 +1,163 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The updated Attitude estimation from @ref AHRSCommsModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The updated Attitude estimation from @ref AHRSCommsModule. + +generated from attitudeactual.xml + **/ +public class AttitudeActual extends UAVDataObject { + + public AttitudeActual() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List q1ElemNames = new ArrayList(); + q1ElemNames.add("0"); + fields.add( new UAVObjectField("q1", "", UAVObjectField.FieldType.FLOAT32, q1ElemNames, null) ); + + List q2ElemNames = new ArrayList(); + q2ElemNames.add("0"); + fields.add( new UAVObjectField("q2", "", UAVObjectField.FieldType.FLOAT32, q2ElemNames, null) ); + + List q3ElemNames = new ArrayList(); + q3ElemNames.add("0"); + fields.add( new UAVObjectField("q3", "", UAVObjectField.FieldType.FLOAT32, q3ElemNames, null) ); + + List q4ElemNames = new ArrayList(); + q4ElemNames.add("0"); + fields.add( new UAVObjectField("q4", "", UAVObjectField.FieldType.FLOAT32, q4ElemNames, null) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "degrees", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "degrees", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "degrees", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 500; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AttitudeActual obj = new AttitudeActual(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AttitudeActual GetInstance(UAVObjectManager objMngr, int instID) + { + return (AttitudeActual)(objMngr.getObject(AttitudeActual.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xFC5B8CF4; + protected static final String NAME = "AttitudeActual"; + protected static String DESCRIPTION = "The updated Attitude estimation from @ref AHRSCommsModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java new file mode 100644 index 000000000..d28302b6a --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java @@ -0,0 +1,158 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. + +generated from attituderaw.xml + **/ +public class AttitudeRaw extends UAVDataObject { + + public AttitudeRaw() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List magnetometersElemNames = new ArrayList(); + magnetometersElemNames.add("X"); + magnetometersElemNames.add("Y"); + magnetometersElemNames.add("Z"); + fields.add( new UAVObjectField("magnetometers", "mGa", UAVObjectField.FieldType.INT16, magnetometersElemNames, null) ); + + List gyrosElemNames = new ArrayList(); + gyrosElemNames.add("X"); + gyrosElemNames.add("Y"); + gyrosElemNames.add("Z"); + fields.add( new UAVObjectField("gyros", "deg/s", UAVObjectField.FieldType.FLOAT32, gyrosElemNames, null) ); + + List gyrotempElemNames = new ArrayList(); + gyrotempElemNames.add("XY"); + gyrotempElemNames.add("Z"); + fields.add( new UAVObjectField("gyrotemp", "raw", UAVObjectField.FieldType.UINT16, gyrotempElemNames, null) ); + + List accelsElemNames = new ArrayList(); + accelsElemNames.add("X"); + accelsElemNames.add("Y"); + accelsElemNames.add("Z"); + fields.add( new UAVObjectField("accels", "m/s^2", UAVObjectField.FieldType.FLOAT32, accelsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AttitudeRaw obj = new AttitudeRaw(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AttitudeRaw GetInstance(UAVObjectManager objMngr, int instID) + { + return (AttitudeRaw)(objMngr.getObject(AttitudeRaw.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x37747DE6; + protected static final String NAME = "AttitudeRaw"; + protected static String DESCRIPTION = "The raw attitude sensor data from @ref AHRSCommsModule. Not always updated."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java new file mode 100644 index 000000000..482fc12ce --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref Attitude module used on CopterControl + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref Attitude module used on CopterControl + +generated from attitudesettings.xml + **/ +public class AttitudeSettings extends UAVDataObject { + + public AttitudeSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AccelBiasElemNames = new ArrayList(); + AccelBiasElemNames.add("X"); + AccelBiasElemNames.add("Y"); + AccelBiasElemNames.add("Z"); + fields.add( new UAVObjectField("AccelBias", "lsb", UAVObjectField.FieldType.INT16, AccelBiasElemNames, null) ); + + List GyroGainElemNames = new ArrayList(); + GyroGainElemNames.add("0"); + fields.add( new UAVObjectField("GyroGain", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, GyroGainElemNames, null) ); + + List AccelKpElemNames = new ArrayList(); + AccelKpElemNames.add("0"); + fields.add( new UAVObjectField("AccelKp", "channel", UAVObjectField.FieldType.FLOAT32, AccelKpElemNames, null) ); + + List AccelKiElemNames = new ArrayList(); + AccelKiElemNames.add("0"); + fields.add( new UAVObjectField("AccelKi", "channel", UAVObjectField.FieldType.FLOAT32, AccelKiElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("AccelBias").setValue(0,0); + getField("AccelBias").setValue(0,1); + getField("AccelBias").setValue(0,2); + getField("GyroGain").setValue(0.42); + getField("AccelKp").setValue(0.01); + getField("AccelKi").setValue(0.0001); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AttitudeSettings obj = new AttitudeSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AttitudeSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (AttitudeSettings)(objMngr.getObject(AttitudeSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x327BF29A; + protected static final String NAME = "AttitudeSettings"; + protected static String DESCRIPTION = "Settings for the @ref Attitude module used on CopterControl"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java new file mode 100644 index 000000000..a2c2c7e3d --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The raw data from the barometric sensor with pressure, temperature and altitude estimate. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The raw data from the barometric sensor with pressure, temperature and altitude estimate. + +generated from baroaltitude.xml + **/ +public class BaroAltitude extends UAVDataObject { + + public BaroAltitude() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List TemperatureElemNames = new ArrayList(); + TemperatureElemNames.add("0"); + fields.add( new UAVObjectField("Temperature", "C", UAVObjectField.FieldType.FLOAT32, TemperatureElemNames, null) ); + + List PressureElemNames = new ArrayList(); + PressureElemNames.add("0"); + fields.add( new UAVObjectField("Pressure", "kPa", UAVObjectField.FieldType.FLOAT32, PressureElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + BaroAltitude obj = new BaroAltitude(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public BaroAltitude GetInstance(UAVObjectManager objMngr, int instID) + { + return (BaroAltitude)(objMngr.getObject(BaroAltitude.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xED4424F6; + protected static final String NAME = "BaroAltitude"; + protected static String DESCRIPTION = "The raw data from the barometric sensor with pressure, temperature and altitude estimate."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java new file mode 100644 index 000000000..19e477b62 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java @@ -0,0 +1,163 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Battery configuration information. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Battery configuration information. + +generated from batterysettings.xml + **/ +public class BatterySettings extends UAVDataObject { + + public BatterySettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List BatteryVoltageElemNames = new ArrayList(); + BatteryVoltageElemNames.add("0"); + fields.add( new UAVObjectField("BatteryVoltage", "V", UAVObjectField.FieldType.FLOAT32, BatteryVoltageElemNames, null) ); + + List BatteryCapacityElemNames = new ArrayList(); + BatteryCapacityElemNames.add("0"); + fields.add( new UAVObjectField("BatteryCapacity", "mAh", UAVObjectField.FieldType.UINT32, BatteryCapacityElemNames, null) ); + + List BatteryTypeElemNames = new ArrayList(); + BatteryTypeElemNames.add("0"); + List BatteryTypeEnumOptions = new ArrayList(); + BatteryTypeEnumOptions.add("LiPo"); + BatteryTypeEnumOptions.add("A123"); + BatteryTypeEnumOptions.add("LiCo"); + BatteryTypeEnumOptions.add("LiFeSO4"); + BatteryTypeEnumOptions.add("None"); + fields.add( new UAVObjectField("BatteryType", "", UAVObjectField.FieldType.ENUM, BatteryTypeElemNames, BatteryTypeEnumOptions) ); + + List CalibrationsElemNames = new ArrayList(); + CalibrationsElemNames.add("Voltage"); + CalibrationsElemNames.add("Current"); + fields.add( new UAVObjectField("Calibrations", "", UAVObjectField.FieldType.FLOAT32, CalibrationsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("BatteryVoltage").setValue(11.1); + getField("BatteryCapacity").setValue(2200); + getField("BatteryType").setValue(0); + getField("Calibrations").setValue(1,0); + getField("Calibrations").setValue(1,1); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + BatterySettings obj = new BatterySettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public BatterySettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (BatterySettings)(objMngr.getObject(BatterySettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA5FF1D9A; + protected static final String NAME = "BatterySettings"; + protected static String DESCRIPTION = "Battery configuration information."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java new file mode 100644 index 000000000..493d6cd64 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java @@ -0,0 +1,258 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Firmware IAP + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Firmware IAP + +generated from firmwareiapobj.xml + **/ +public class FirmwareIAPObj extends UAVDataObject { + + public FirmwareIAPObj() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List CommandElemNames = new ArrayList(); + CommandElemNames.add("0"); + fields.add( new UAVObjectField("Command", "", UAVObjectField.FieldType.UINT16, CommandElemNames, null) ); + + List DescriptionElemNames = new ArrayList(); + DescriptionElemNames.add("0"); + DescriptionElemNames.add("1"); + DescriptionElemNames.add("2"); + DescriptionElemNames.add("3"); + DescriptionElemNames.add("4"); + DescriptionElemNames.add("5"); + DescriptionElemNames.add("6"); + DescriptionElemNames.add("7"); + DescriptionElemNames.add("8"); + DescriptionElemNames.add("9"); + DescriptionElemNames.add("10"); + DescriptionElemNames.add("11"); + DescriptionElemNames.add("12"); + DescriptionElemNames.add("13"); + DescriptionElemNames.add("14"); + DescriptionElemNames.add("15"); + DescriptionElemNames.add("16"); + DescriptionElemNames.add("17"); + DescriptionElemNames.add("18"); + DescriptionElemNames.add("19"); + DescriptionElemNames.add("20"); + DescriptionElemNames.add("21"); + DescriptionElemNames.add("22"); + DescriptionElemNames.add("23"); + DescriptionElemNames.add("24"); + DescriptionElemNames.add("25"); + DescriptionElemNames.add("26"); + DescriptionElemNames.add("27"); + DescriptionElemNames.add("28"); + DescriptionElemNames.add("29"); + DescriptionElemNames.add("30"); + DescriptionElemNames.add("31"); + DescriptionElemNames.add("32"); + DescriptionElemNames.add("33"); + DescriptionElemNames.add("34"); + DescriptionElemNames.add("35"); + DescriptionElemNames.add("36"); + DescriptionElemNames.add("37"); + DescriptionElemNames.add("38"); + DescriptionElemNames.add("39"); + DescriptionElemNames.add("40"); + DescriptionElemNames.add("41"); + DescriptionElemNames.add("42"); + DescriptionElemNames.add("43"); + DescriptionElemNames.add("44"); + DescriptionElemNames.add("45"); + DescriptionElemNames.add("46"); + DescriptionElemNames.add("47"); + DescriptionElemNames.add("48"); + DescriptionElemNames.add("49"); + DescriptionElemNames.add("50"); + DescriptionElemNames.add("51"); + DescriptionElemNames.add("52"); + DescriptionElemNames.add("53"); + DescriptionElemNames.add("54"); + DescriptionElemNames.add("55"); + DescriptionElemNames.add("56"); + DescriptionElemNames.add("57"); + DescriptionElemNames.add("58"); + DescriptionElemNames.add("59"); + DescriptionElemNames.add("60"); + DescriptionElemNames.add("61"); + DescriptionElemNames.add("62"); + DescriptionElemNames.add("63"); + DescriptionElemNames.add("64"); + DescriptionElemNames.add("65"); + DescriptionElemNames.add("66"); + DescriptionElemNames.add("67"); + DescriptionElemNames.add("68"); + DescriptionElemNames.add("69"); + DescriptionElemNames.add("70"); + DescriptionElemNames.add("71"); + DescriptionElemNames.add("72"); + DescriptionElemNames.add("73"); + DescriptionElemNames.add("74"); + DescriptionElemNames.add("75"); + DescriptionElemNames.add("76"); + DescriptionElemNames.add("77"); + DescriptionElemNames.add("78"); + DescriptionElemNames.add("79"); + DescriptionElemNames.add("80"); + DescriptionElemNames.add("81"); + DescriptionElemNames.add("82"); + DescriptionElemNames.add("83"); + DescriptionElemNames.add("84"); + DescriptionElemNames.add("85"); + DescriptionElemNames.add("86"); + DescriptionElemNames.add("87"); + DescriptionElemNames.add("88"); + DescriptionElemNames.add("89"); + DescriptionElemNames.add("90"); + DescriptionElemNames.add("91"); + DescriptionElemNames.add("92"); + DescriptionElemNames.add("93"); + DescriptionElemNames.add("94"); + DescriptionElemNames.add("95"); + DescriptionElemNames.add("96"); + DescriptionElemNames.add("97"); + DescriptionElemNames.add("98"); + DescriptionElemNames.add("99"); + fields.add( new UAVObjectField("Description", "", UAVObjectField.FieldType.UINT8, DescriptionElemNames, null) ); + + List BoardRevisionElemNames = new ArrayList(); + BoardRevisionElemNames.add("0"); + fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); + + List BoardTypeElemNames = new ArrayList(); + BoardTypeElemNames.add("0"); + fields.add( new UAVObjectField("BoardType", "", UAVObjectField.FieldType.UINT8, BoardTypeElemNames, null) ); + + List ArmResetElemNames = new ArrayList(); + ArmResetElemNames.add("0"); + fields.add( new UAVObjectField("ArmReset", "", UAVObjectField.FieldType.UINT8, ArmResetElemNames, null) ); + + List crcElemNames = new ArrayList(); + crcElemNames.add("0"); + fields.add( new UAVObjectField("crc", "", UAVObjectField.FieldType.UINT32, crcElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FirmwareIAPObj obj = new FirmwareIAPObj(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FirmwareIAPObj GetInstance(UAVObjectManager objMngr, int instID) + { + return (FirmwareIAPObj)(objMngr.getObject(FirmwareIAPObj.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1A8ECC2; + protected static final String NAME = "FirmwareIAPObj"; + protected static String DESCRIPTION = "Firmware IAP"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java new file mode 100644 index 000000000..d9fba1de5 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java @@ -0,0 +1,165 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Battery status information. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Battery status information. + +generated from flightbatterystate.xml + **/ +public class FlightBatteryState extends UAVDataObject { + + public FlightBatteryState() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List VoltageElemNames = new ArrayList(); + VoltageElemNames.add("0"); + fields.add( new UAVObjectField("Voltage", "V", UAVObjectField.FieldType.FLOAT32, VoltageElemNames, null) ); + + List CurrentElemNames = new ArrayList(); + CurrentElemNames.add("0"); + fields.add( new UAVObjectField("Current", "A", UAVObjectField.FieldType.FLOAT32, CurrentElemNames, null) ); + + List PeakCurrentElemNames = new ArrayList(); + PeakCurrentElemNames.add("0"); + fields.add( new UAVObjectField("PeakCurrent", "A", UAVObjectField.FieldType.FLOAT32, PeakCurrentElemNames, null) ); + + List AvgCurrentElemNames = new ArrayList(); + AvgCurrentElemNames.add("0"); + fields.add( new UAVObjectField("AvgCurrent", "A", UAVObjectField.FieldType.FLOAT32, AvgCurrentElemNames, null) ); + + List ConsumedEnergyElemNames = new ArrayList(); + ConsumedEnergyElemNames.add("0"); + fields.add( new UAVObjectField("ConsumedEnergy", "mAh", UAVObjectField.FieldType.FLOAT32, ConsumedEnergyElemNames, null) ); + + List EstimatedFlightTimeElemNames = new ArrayList(); + EstimatedFlightTimeElemNames.add("0"); + fields.add( new UAVObjectField("EstimatedFlightTime", "sec", UAVObjectField.FieldType.FLOAT32, EstimatedFlightTimeElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READONLY; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Voltage").setValue(0); + getField("Current").setValue(0); + getField("PeakCurrent").setValue(0); + getField("AvgCurrent").setValue(0); + getField("ConsumedEnergy").setValue(0); + getField("EstimatedFlightTime").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightBatteryState obj = new FlightBatteryState(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightBatteryState GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightBatteryState)(objMngr.getObject(FlightBatteryState.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x791A50E; + protected static final String NAME = "FlightBatteryState"; + protected static String DESCRIPTION = "Battery status information."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java new file mode 100644 index 000000000..2e453eda5 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java @@ -0,0 +1,144 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Control the flight plan script + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Control the flight plan script + +generated from flightplancontrol.xml + **/ +public class FlightPlanControl extends UAVDataObject { + + public FlightPlanControl() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List CommandElemNames = new ArrayList(); + CommandElemNames.add("0"); + List CommandEnumOptions = new ArrayList(); + CommandEnumOptions.add("Start"); + CommandEnumOptions.add("Stop"); + CommandEnumOptions.add("Kill"); + fields.add( new UAVObjectField("Command", "", UAVObjectField.FieldType.ENUM, CommandElemNames, CommandEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Command").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightPlanControl obj = new FlightPlanControl(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightPlanControl GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightPlanControl)(objMngr.getObject(FlightPlanControl.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x6B4FE6DA; + protected static final String NAME = "FlightPlanControl"; + protected static String DESCRIPTION = "Control the flight plan script"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java new file mode 100644 index 000000000..383e4aff0 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java @@ -0,0 +1,140 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the flight plan module, control the execution of the script + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the flight plan module, control the execution of the script + +generated from flightplansettings.xml + **/ +public class FlightPlanSettings extends UAVDataObject { + + public FlightPlanSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List TestElemNames = new ArrayList(); + TestElemNames.add("0"); + fields.add( new UAVObjectField("Test", "", UAVObjectField.FieldType.FLOAT32, TestElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Test").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightPlanSettings obj = new FlightPlanSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightPlanSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightPlanSettings)(objMngr.getObject(FlightPlanSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x85368422; + protected static final String NAME = "FlightPlanSettings"; + protected static String DESCRIPTION = "Settings for the flight plan module, control the execution of the script"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java new file mode 100644 index 000000000..00920553c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java @@ -0,0 +1,187 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Status of the flight plan script + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Status of the flight plan script + +generated from flightplanstatus.xml + **/ +public class FlightPlanStatus extends UAVDataObject { + + public FlightPlanStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Stopped"); + StatusEnumOptions.add("Running"); + StatusEnumOptions.add("Error"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List ErrorTypeElemNames = new ArrayList(); + ErrorTypeElemNames.add("0"); + List ErrorTypeEnumOptions = new ArrayList(); + ErrorTypeEnumOptions.add("None"); + ErrorTypeEnumOptions.add("VMInitError"); + ErrorTypeEnumOptions.add("Exception"); + ErrorTypeEnumOptions.add("IOError"); + ErrorTypeEnumOptions.add("DivByZero"); + ErrorTypeEnumOptions.add("AssertError"); + ErrorTypeEnumOptions.add("AttributeError"); + ErrorTypeEnumOptions.add("ImportError"); + ErrorTypeEnumOptions.add("IndexError"); + ErrorTypeEnumOptions.add("KeyError"); + ErrorTypeEnumOptions.add("MemoryError"); + ErrorTypeEnumOptions.add("NameError"); + ErrorTypeEnumOptions.add("SyntaxError"); + ErrorTypeEnumOptions.add("SystemError"); + ErrorTypeEnumOptions.add("TypeError"); + ErrorTypeEnumOptions.add("ValueError"); + ErrorTypeEnumOptions.add("StopIteration"); + ErrorTypeEnumOptions.add("Warning"); + ErrorTypeEnumOptions.add("UnknownError"); + fields.add( new UAVObjectField("ErrorType", "", UAVObjectField.FieldType.ENUM, ErrorTypeElemNames, ErrorTypeEnumOptions) ); + + List ErrorFileIDElemNames = new ArrayList(); + ErrorFileIDElemNames.add("0"); + fields.add( new UAVObjectField("ErrorFileID", "", UAVObjectField.FieldType.UINT32, ErrorFileIDElemNames, null) ); + + List ErrorLineNumElemNames = new ArrayList(); + ErrorLineNumElemNames.add("0"); + fields.add( new UAVObjectField("ErrorLineNum", "", UAVObjectField.FieldType.UINT32, ErrorLineNumElemNames, null) ); + + List Debug1ElemNames = new ArrayList(); + Debug1ElemNames.add("0"); + fields.add( new UAVObjectField("Debug1", "", UAVObjectField.FieldType.FLOAT32, Debug1ElemNames, null) ); + + List Debug2ElemNames = new ArrayList(); + Debug2ElemNames.add("0"); + fields.add( new UAVObjectField("Debug2", "", UAVObjectField.FieldType.FLOAT32, Debug2ElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 2000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Status").setValue(0); + getField("ErrorType").setValue(0); + getField("Debug1").setValue(0); + getField("Debug2").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightPlanStatus obj = new FlightPlanStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightPlanStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightPlanStatus)(objMngr.getObject(FlightPlanStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x9FC14812; + protected static final String NAME = "FlightPlanStatus"; + protected static String DESCRIPTION = "Status of the flight plan script"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java new file mode 100644 index 000000000..b58fe6d46 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java @@ -0,0 +1,164 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Maintains the telemetry statistics from the OpenPilot flight computer. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Maintains the telemetry statistics from the OpenPilot flight computer. + +generated from flighttelemetrystats.xml + **/ +public class FlightTelemetryStats extends UAVDataObject { + + public FlightTelemetryStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Disconnected"); + StatusEnumOptions.add("HandshakeReq"); + StatusEnumOptions.add("HandshakeAck"); + StatusEnumOptions.add("Connected"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List TxDataRateElemNames = new ArrayList(); + TxDataRateElemNames.add("0"); + fields.add( new UAVObjectField("TxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, TxDataRateElemNames, null) ); + + List RxDataRateElemNames = new ArrayList(); + RxDataRateElemNames.add("0"); + fields.add( new UAVObjectField("RxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, RxDataRateElemNames, null) ); + + List TxFailuresElemNames = new ArrayList(); + TxFailuresElemNames.add("0"); + fields.add( new UAVObjectField("TxFailures", "count", UAVObjectField.FieldType.UINT32, TxFailuresElemNames, null) ); + + List RxFailuresElemNames = new ArrayList(); + RxFailuresElemNames.add("0"); + fields.add( new UAVObjectField("RxFailures", "count", UAVObjectField.FieldType.UINT32, RxFailuresElemNames, null) ); + + List TxRetriesElemNames = new ArrayList(); + TxRetriesElemNames.add("0"); + fields.add( new UAVObjectField("TxRetries", "count", UAVObjectField.FieldType.UINT32, TxRetriesElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 5000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 5000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightTelemetryStats obj = new FlightTelemetryStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightTelemetryStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightTelemetryStats)(objMngr.getObject(FlightTelemetryStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x660C265E; + protected static final String NAME = "FlightTelemetryStats"; + protected static String DESCRIPTION = "Maintains the telemetry statistics from the OpenPilot flight computer."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java new file mode 100644 index 000000000..0f304d45d --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java @@ -0,0 +1,164 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The telemetry statistics from the ground computer + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The telemetry statistics from the ground computer + +generated from gcstelemetrystats.xml + **/ +public class GCSTelemetryStats extends UAVDataObject { + + public GCSTelemetryStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Disconnected"); + StatusEnumOptions.add("HandshakeReq"); + StatusEnumOptions.add("HandshakeAck"); + StatusEnumOptions.add("Connected"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List TxDataRateElemNames = new ArrayList(); + TxDataRateElemNames.add("0"); + fields.add( new UAVObjectField("TxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, TxDataRateElemNames, null) ); + + List RxDataRateElemNames = new ArrayList(); + RxDataRateElemNames.add("0"); + fields.add( new UAVObjectField("RxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, RxDataRateElemNames, null) ); + + List TxFailuresElemNames = new ArrayList(); + TxFailuresElemNames.add("0"); + fields.add( new UAVObjectField("TxFailures", "count", UAVObjectField.FieldType.UINT32, TxFailuresElemNames, null) ); + + List RxFailuresElemNames = new ArrayList(); + RxFailuresElemNames.add("0"); + fields.add( new UAVObjectField("RxFailures", "count", UAVObjectField.FieldType.UINT32, RxFailuresElemNames, null) ); + + List TxRetriesElemNames = new ArrayList(); + TxRetriesElemNames.add("0"); + fields.add( new UAVObjectField("TxRetries", "count", UAVObjectField.FieldType.UINT32, TxRetriesElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.gcsTelemetryUpdatePeriod = 5000; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GCSTelemetryStats obj = new GCSTelemetryStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GCSTelemetryStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (GCSTelemetryStats)(objMngr.getObject(GCSTelemetryStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x771E1046; + protected static final String NAME = "GCSTelemetryStats"; + protected static String DESCRIPTION = "The telemetry statistics from the ground computer"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java new file mode 100644 index 000000000..889091e0e --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java @@ -0,0 +1,184 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule. + +generated from gpsposition.xml + **/ +public class GPSPosition extends UAVDataObject { + + public GPSPosition() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("NoGPS"); + StatusEnumOptions.add("NoFix"); + StatusEnumOptions.add("Fix2D"); + StatusEnumOptions.add("Fix3D"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List LatitudeElemNames = new ArrayList(); + LatitudeElemNames.add("0"); + fields.add( new UAVObjectField("Latitude", "degrees x 10^-7", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); + + List LongitudeElemNames = new ArrayList(); + LongitudeElemNames.add("0"); + fields.add( new UAVObjectField("Longitude", "degrees x 10^-7", UAVObjectField.FieldType.INT32, LongitudeElemNames, null) ); + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "meters", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List GeoidSeparationElemNames = new ArrayList(); + GeoidSeparationElemNames.add("0"); + fields.add( new UAVObjectField("GeoidSeparation", "meters", UAVObjectField.FieldType.FLOAT32, GeoidSeparationElemNames, null) ); + + List HeadingElemNames = new ArrayList(); + HeadingElemNames.add("0"); + fields.add( new UAVObjectField("Heading", "degrees", UAVObjectField.FieldType.FLOAT32, HeadingElemNames, null) ); + + List GroundspeedElemNames = new ArrayList(); + GroundspeedElemNames.add("0"); + fields.add( new UAVObjectField("Groundspeed", "m/s", UAVObjectField.FieldType.FLOAT32, GroundspeedElemNames, null) ); + + List SatellitesElemNames = new ArrayList(); + SatellitesElemNames.add("0"); + fields.add( new UAVObjectField("Satellites", "", UAVObjectField.FieldType.INT8, SatellitesElemNames, null) ); + + List PDOPElemNames = new ArrayList(); + PDOPElemNames.add("0"); + fields.add( new UAVObjectField("PDOP", "", UAVObjectField.FieldType.FLOAT32, PDOPElemNames, null) ); + + List HDOPElemNames = new ArrayList(); + HDOPElemNames.add("0"); + fields.add( new UAVObjectField("HDOP", "", UAVObjectField.FieldType.FLOAT32, HDOPElemNames, null) ); + + List VDOPElemNames = new ArrayList(); + VDOPElemNames.add("0"); + fields.add( new UAVObjectField("VDOP", "", UAVObjectField.FieldType.FLOAT32, VDOPElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSPosition obj = new GPSPosition(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSPosition GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSPosition)(objMngr.getObject(GPSPosition.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xB5495042; + protected static final String NAME = "GPSPosition"; + protected static String DESCRIPTION = "Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java new file mode 100644 index 000000000..fa1100207 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java @@ -0,0 +1,215 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains information about the GPS satellites in view from @ref GPSModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains information about the GPS satellites in view from @ref GPSModule. + +generated from gpssatellites.xml + **/ +public class GPSSatellites extends UAVDataObject { + + public GPSSatellites() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SatsInViewElemNames = new ArrayList(); + SatsInViewElemNames.add("0"); + fields.add( new UAVObjectField("SatsInView", "", UAVObjectField.FieldType.INT8, SatsInViewElemNames, null) ); + + List PRNElemNames = new ArrayList(); + PRNElemNames.add("0"); + PRNElemNames.add("1"); + PRNElemNames.add("2"); + PRNElemNames.add("3"); + PRNElemNames.add("4"); + PRNElemNames.add("5"); + PRNElemNames.add("6"); + PRNElemNames.add("7"); + PRNElemNames.add("8"); + PRNElemNames.add("9"); + PRNElemNames.add("10"); + PRNElemNames.add("11"); + PRNElemNames.add("12"); + PRNElemNames.add("13"); + PRNElemNames.add("14"); + PRNElemNames.add("15"); + fields.add( new UAVObjectField("PRN", "", UAVObjectField.FieldType.INT8, PRNElemNames, null) ); + + List ElevationElemNames = new ArrayList(); + ElevationElemNames.add("0"); + ElevationElemNames.add("1"); + ElevationElemNames.add("2"); + ElevationElemNames.add("3"); + ElevationElemNames.add("4"); + ElevationElemNames.add("5"); + ElevationElemNames.add("6"); + ElevationElemNames.add("7"); + ElevationElemNames.add("8"); + ElevationElemNames.add("9"); + ElevationElemNames.add("10"); + ElevationElemNames.add("11"); + ElevationElemNames.add("12"); + ElevationElemNames.add("13"); + ElevationElemNames.add("14"); + ElevationElemNames.add("15"); + fields.add( new UAVObjectField("Elevation", "degrees", UAVObjectField.FieldType.FLOAT32, ElevationElemNames, null) ); + + List AzimuthElemNames = new ArrayList(); + AzimuthElemNames.add("0"); + AzimuthElemNames.add("1"); + AzimuthElemNames.add("2"); + AzimuthElemNames.add("3"); + AzimuthElemNames.add("4"); + AzimuthElemNames.add("5"); + AzimuthElemNames.add("6"); + AzimuthElemNames.add("7"); + AzimuthElemNames.add("8"); + AzimuthElemNames.add("9"); + AzimuthElemNames.add("10"); + AzimuthElemNames.add("11"); + AzimuthElemNames.add("12"); + AzimuthElemNames.add("13"); + AzimuthElemNames.add("14"); + AzimuthElemNames.add("15"); + fields.add( new UAVObjectField("Azimuth", "degrees", UAVObjectField.FieldType.FLOAT32, AzimuthElemNames, null) ); + + List SNRElemNames = new ArrayList(); + SNRElemNames.add("0"); + SNRElemNames.add("1"); + SNRElemNames.add("2"); + SNRElemNames.add("3"); + SNRElemNames.add("4"); + SNRElemNames.add("5"); + SNRElemNames.add("6"); + SNRElemNames.add("7"); + SNRElemNames.add("8"); + SNRElemNames.add("9"); + SNRElemNames.add("10"); + SNRElemNames.add("11"); + SNRElemNames.add("12"); + SNRElemNames.add("13"); + SNRElemNames.add("14"); + SNRElemNames.add("15"); + fields.add( new UAVObjectField("SNR", "", UAVObjectField.FieldType.INT8, SNRElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 30000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSSatellites obj = new GPSSatellites(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSSatellites GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSSatellites)(objMngr.getObject(GPSSatellites.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD62FA3AE; + protected static final String NAME = "GPSSatellites"; + protected static String DESCRIPTION = "Contains information about the GPS satellites in view from @ref GPSModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java new file mode 100644 index 000000000..5ff55cc2e --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location. + +generated from gpstime.xml + **/ +public class GPSTime extends UAVDataObject { + + public GPSTime() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List MonthElemNames = new ArrayList(); + MonthElemNames.add("0"); + fields.add( new UAVObjectField("Month", "", UAVObjectField.FieldType.INT8, MonthElemNames, null) ); + + List DayElemNames = new ArrayList(); + DayElemNames.add("0"); + fields.add( new UAVObjectField("Day", "", UAVObjectField.FieldType.INT8, DayElemNames, null) ); + + List YearElemNames = new ArrayList(); + YearElemNames.add("0"); + fields.add( new UAVObjectField("Year", "", UAVObjectField.FieldType.INT16, YearElemNames, null) ); + + List HourElemNames = new ArrayList(); + HourElemNames.add("0"); + fields.add( new UAVObjectField("Hour", "", UAVObjectField.FieldType.INT8, HourElemNames, null) ); + + List MinuteElemNames = new ArrayList(); + MinuteElemNames.add("0"); + fields.add( new UAVObjectField("Minute", "", UAVObjectField.FieldType.INT8, MinuteElemNames, null) ); + + List SecondElemNames = new ArrayList(); + SecondElemNames.add("0"); + fields.add( new UAVObjectField("Second", "", UAVObjectField.FieldType.INT8, SecondElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 30000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSTime obj = new GPSTime(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSTime GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSTime)(objMngr.getObject(GPSTime.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x56FFF0A2; + protected static final String NAME = "GPSTime"; + protected static String DESCRIPTION = "Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java new file mode 100644 index 000000000..2cde12f64 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java @@ -0,0 +1,197 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref GuidanceModule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref GuidanceModule + +generated from guidancesettings.xml + **/ +public class GuidanceSettings extends UAVDataObject { + + public GuidanceSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List GuidanceModeElemNames = new ArrayList(); + GuidanceModeElemNames.add("0"); + List GuidanceModeEnumOptions = new ArrayList(); + GuidanceModeEnumOptions.add("DUAL_LOOP"); + GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); + fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); + + List HorizontalPElemNames = new ArrayList(); + HorizontalPElemNames.add("Kp"); + HorizontalPElemNames.add("Max"); + fields.add( new UAVObjectField("HorizontalP", "", UAVObjectField.FieldType.FLOAT32, HorizontalPElemNames, null) ); + + List HorizontalVelPIDElemNames = new ArrayList(); + HorizontalVelPIDElemNames.add("Kp"); + HorizontalVelPIDElemNames.add("Ki"); + HorizontalVelPIDElemNames.add("Kd"); + HorizontalVelPIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("HorizontalVelPID", "", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); + + List VerticalPElemNames = new ArrayList(); + VerticalPElemNames.add("Kp"); + VerticalPElemNames.add("Max"); + fields.add( new UAVObjectField("VerticalP", "", UAVObjectField.FieldType.FLOAT32, VerticalPElemNames, null) ); + + List VerticalVelPIDElemNames = new ArrayList(); + VerticalVelPIDElemNames.add("Kp"); + VerticalVelPIDElemNames.add("Ki"); + VerticalVelPIDElemNames.add("Kd"); + VerticalVelPIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); + + List ThrottleControlElemNames = new ArrayList(); + ThrottleControlElemNames.add("0"); + List ThrottleControlEnumOptions = new ArrayList(); + ThrottleControlEnumOptions.add("FALSE"); + ThrottleControlEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); + + List MaxRollPitchElemNames = new ArrayList(); + MaxRollPitchElemNames.add("0"); + fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); + + List UpdatePeriodElemNames = new ArrayList(); + UpdatePeriodElemNames.add("0"); + fields.add( new UAVObjectField("UpdatePeriod", "", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("GuidanceMode").setValue(0); + getField("HorizontalP").setValue(0.2,0); + getField("HorizontalP").setValue(150,1); + getField("HorizontalVelPID").setValue(0.1,0); + getField("HorizontalVelPID").setValue(0.002,1); + getField("HorizontalVelPID").setValue(0,2); + getField("HorizontalVelPID").setValue(1000,3); + getField("VerticalP").setValue(0.1,0); + getField("VerticalP").setValue(200,1); + getField("VerticalVelPID").setValue(0.1,0); + getField("VerticalVelPID").setValue(0,1); + getField("VerticalVelPID").setValue(0,2); + getField("VerticalVelPID").setValue(0,3); + getField("ThrottleControl").setValue(0); + getField("MaxRollPitch").setValue(10); + getField("UpdatePeriod").setValue(100); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GuidanceSettings obj = new GuidanceSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GuidanceSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (GuidanceSettings)(objMngr.getObject(GuidanceSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x74740AA2; + protected static final String NAME = "GuidanceSettings"; + protected static String DESCRIPTION = "Settings for the @ref GuidanceModule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java new file mode 100644 index 000000000..2adebce70 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -0,0 +1,197 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule. + +generated from homelocation.xml + **/ +public class HomeLocation extends UAVDataObject { + + public HomeLocation() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SetElemNames = new ArrayList(); + SetElemNames.add("0"); + List SetEnumOptions = new ArrayList(); + SetEnumOptions.add("FALSE"); + SetEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("Set", "", UAVObjectField.FieldType.ENUM, SetElemNames, SetEnumOptions) ); + + List LatitudeElemNames = new ArrayList(); + LatitudeElemNames.add("0"); + fields.add( new UAVObjectField("Latitude", "deg * 10e6", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); + + List LongitudeElemNames = new ArrayList(); + LongitudeElemNames.add("0"); + fields.add( new UAVObjectField("Longitude", "deg * 10e6", UAVObjectField.FieldType.INT32, LongitudeElemNames, null) ); + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m over geoid", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List ECEFElemNames = new ArrayList(); + ECEFElemNames.add("0"); + ECEFElemNames.add("1"); + ECEFElemNames.add("2"); + fields.add( new UAVObjectField("ECEF", "cm", UAVObjectField.FieldType.INT32, ECEFElemNames, null) ); + + List RNEElemNames = new ArrayList(); + RNEElemNames.add("0"); + RNEElemNames.add("1"); + RNEElemNames.add("2"); + RNEElemNames.add("3"); + RNEElemNames.add("4"); + RNEElemNames.add("5"); + RNEElemNames.add("6"); + RNEElemNames.add("7"); + RNEElemNames.add("8"); + fields.add( new UAVObjectField("RNE", "", UAVObjectField.FieldType.FLOAT32, RNEElemNames, null) ); + + List BeElemNames = new ArrayList(); + BeElemNames.add("0"); + BeElemNames.add("1"); + BeElemNames.add("2"); + fields.add( new UAVObjectField("Be", "", UAVObjectField.FieldType.FLOAT32, BeElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Set").setValue(0); + getField("Latitude").setValue(0); + getField("Longitude").setValue(0); + getField("Altitude").setValue(0); + getField("ECEF").setValue(0,0); + getField("ECEF").setValue(0,1); + getField("ECEF").setValue(0,2); + getField("RNE").setValue(0,0); + getField("RNE").setValue(0,1); + getField("RNE").setValue(0,2); + getField("RNE").setValue(0,3); + getField("RNE").setValue(0,4); + getField("RNE").setValue(0,5); + getField("RNE").setValue(0,6); + getField("RNE").setValue(0,7); + getField("RNE").setValue(0,8); + getField("Be").setValue(0,0); + getField("Be").setValue(0,1); + getField("Be").setValue(0,2); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + HomeLocation obj = new HomeLocation(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public HomeLocation GetInstance(UAVObjectManager objMngr, int instID) + { + return (HomeLocation)(objMngr.getObject(HomeLocation.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD6008ED2; + protected static final String NAME = "HomeLocation"; + protected static String DESCRIPTION = "HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java new file mode 100644 index 000000000..fc68e2902 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java @@ -0,0 +1,238 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Tracks statistics on the I2C bus. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Tracks statistics on the I2C bus. + +generated from i2cstats.xml + **/ +public class I2CStats extends UAVDataObject { + + public I2CStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List event_errorsElemNames = new ArrayList(); + event_errorsElemNames.add("0"); + fields.add( new UAVObjectField("event_errors", "", UAVObjectField.FieldType.UINT8, event_errorsElemNames, null) ); + + List fsm_errorsElemNames = new ArrayList(); + fsm_errorsElemNames.add("0"); + fields.add( new UAVObjectField("fsm_errors", "", UAVObjectField.FieldType.UINT8, fsm_errorsElemNames, null) ); + + List irq_errorsElemNames = new ArrayList(); + irq_errorsElemNames.add("0"); + fields.add( new UAVObjectField("irq_errors", "", UAVObjectField.FieldType.UINT8, irq_errorsElemNames, null) ); + + List nacksElemNames = new ArrayList(); + nacksElemNames.add("0"); + fields.add( new UAVObjectField("nacks", "", UAVObjectField.FieldType.UINT8, nacksElemNames, null) ); + + List timeoutsElemNames = new ArrayList(); + timeoutsElemNames.add("0"); + fields.add( new UAVObjectField("timeouts", "", UAVObjectField.FieldType.UINT8, timeoutsElemNames, null) ); + + List last_error_typeElemNames = new ArrayList(); + last_error_typeElemNames.add("0"); + List last_error_typeEnumOptions = new ArrayList(); + last_error_typeEnumOptions.add("EVENT"); + last_error_typeEnumOptions.add("FSM"); + last_error_typeEnumOptions.add("INTERRUPT"); + fields.add( new UAVObjectField("last_error_type", "", UAVObjectField.FieldType.ENUM, last_error_typeElemNames, last_error_typeEnumOptions) ); + + List evirq_logElemNames = new ArrayList(); + evirq_logElemNames.add("0"); + evirq_logElemNames.add("1"); + evirq_logElemNames.add("2"); + evirq_logElemNames.add("3"); + evirq_logElemNames.add("4"); + fields.add( new UAVObjectField("evirq_log", "", UAVObjectField.FieldType.UINT32, evirq_logElemNames, null) ); + + List erirq_logElemNames = new ArrayList(); + erirq_logElemNames.add("0"); + erirq_logElemNames.add("1"); + erirq_logElemNames.add("2"); + erirq_logElemNames.add("3"); + erirq_logElemNames.add("4"); + fields.add( new UAVObjectField("erirq_log", "", UAVObjectField.FieldType.UINT32, erirq_logElemNames, null) ); + + List event_logElemNames = new ArrayList(); + event_logElemNames.add("0"); + event_logElemNames.add("1"); + event_logElemNames.add("2"); + event_logElemNames.add("3"); + event_logElemNames.add("4"); + List event_logEnumOptions = new ArrayList(); + event_logEnumOptions.add("I2C_EVENT_BUS_ERROR"); + event_logEnumOptions.add("I2C_EVENT_START"); + event_logEnumOptions.add("I2C_EVENT_STARTED_MORE_TXN_READ"); + event_logEnumOptions.add("I2C_EVENT_STARTED_MORE_TXN_WRITE"); + event_logEnumOptions.add("I2C_EVENT_STARTED_LAST_TXN_READ"); + event_logEnumOptions.add("I2C_EVENT_STARTED_LAST_TXN_WRITE"); + event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_EQ_0"); + event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_EQ_1"); + event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_EQ_2"); + event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_GT_2"); + event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_EQ_0"); + event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_EQ_1"); + event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_EQ_2"); + event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_GT_2"); + event_logEnumOptions.add("I2C_EVENT_NACK"); + event_logEnumOptions.add("I2C_EVENT_STOPPED"); + event_logEnumOptions.add("I2C_EVENT_AUTO"); + fields.add( new UAVObjectField("event_log", "", UAVObjectField.FieldType.ENUM, event_logElemNames, event_logEnumOptions) ); + + List state_logElemNames = new ArrayList(); + state_logElemNames.add("0"); + state_logElemNames.add("1"); + state_logElemNames.add("2"); + state_logElemNames.add("3"); + state_logElemNames.add("4"); + List state_logEnumOptions = new ArrayList(); + state_logEnumOptions.add("I2C_STATE_FSM_FAULT"); + state_logEnumOptions.add("I2C_STATE_BUS_ERROR"); + state_logEnumOptions.add("I2C_STATE_STOPPED"); + state_logEnumOptions.add("I2C_STATE_STOPPING"); + state_logEnumOptions.add("I2C_STATE_STARTING"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_ADDR"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_PRE_ONE"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_PRE_FIRST"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_PRE_MIDDLE"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_LAST"); + state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_POST_LAST"); + state_logEnumOptions.add("R_LAST_TXN_ADDR"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_ONE"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_FIRST"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_MIDDLE"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_LAST"); + state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_POST_LAST"); + state_logEnumOptions.add("I2C_STATE_W_MORE_TXN_ADDR"); + state_logEnumOptions.add("I2C_STATE_W_MORE_TXN_MIDDLE"); + state_logEnumOptions.add("I2C_STATE_W_MORE_TXN_LAST"); + state_logEnumOptions.add("I2C_STATE_W_LAST_TXN_ADDR"); + state_logEnumOptions.add("I2C_STATE_W_LAST_TXN_MIDDLE"); + state_logEnumOptions.add("I2C_STATE_W_LAST_TXN_LAST"); + state_logEnumOptions.add("I2C_STATE_NACK"); + fields.add( new UAVObjectField("state_log", "", UAVObjectField.FieldType.ENUM, state_logElemNames, state_logEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 30000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + I2CStats obj = new I2CStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public I2CStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (I2CStats)(objMngr.getObject(I2CStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x23CE9E9C; + protected static final String NAME = "I2CStats"; + protected static String DESCRIPTION = "Tracks statistics on the I2C bus."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java new file mode 100644 index 000000000..636f30946 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java @@ -0,0 +1,199 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control. + +generated from manualcontrolcommand.xml + **/ +public class ManualControlCommand extends UAVDataObject { + + public ManualControlCommand() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ConnectedElemNames = new ArrayList(); + ConnectedElemNames.add("0"); + List ConnectedEnumOptions = new ArrayList(); + ConnectedEnumOptions.add("False"); + ConnectedEnumOptions.add("True"); + fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); + + List ArmedElemNames = new ArrayList(); + ArmedElemNames.add("0"); + List ArmedEnumOptions = new ArrayList(); + ArmedEnumOptions.add("False"); + ArmedEnumOptions.add("True"); + fields.add( new UAVObjectField("Armed", "", UAVObjectField.FieldType.ENUM, ArmedElemNames, ArmedEnumOptions) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "%", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "%", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "%", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); + + List FlightModeElemNames = new ArrayList(); + FlightModeElemNames.add("0"); + List FlightModeEnumOptions = new ArrayList(); + FlightModeEnumOptions.add("Manual"); + FlightModeEnumOptions.add("Stabilized1"); + FlightModeEnumOptions.add("Stabilized2"); + FlightModeEnumOptions.add("Stabilized3"); + FlightModeEnumOptions.add("VelocityControl"); + FlightModeEnumOptions.add("PositionHold"); + fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); + + List Accessory1ElemNames = new ArrayList(); + Accessory1ElemNames.add("0"); + fields.add( new UAVObjectField("Accessory1", "%", UAVObjectField.FieldType.FLOAT32, Accessory1ElemNames, null) ); + + List Accessory2ElemNames = new ArrayList(); + Accessory2ElemNames.add("0"); + fields.add( new UAVObjectField("Accessory2", "%", UAVObjectField.FieldType.FLOAT32, Accessory2ElemNames, null) ); + + List Accessory3ElemNames = new ArrayList(); + Accessory3ElemNames.add("0"); + fields.add( new UAVObjectField("Accessory3", "%", UAVObjectField.FieldType.FLOAT32, Accessory3ElemNames, null) ); + + List ChannelElemNames = new ArrayList(); + ChannelElemNames.add("0"); + ChannelElemNames.add("1"); + ChannelElemNames.add("2"); + ChannelElemNames.add("3"); + ChannelElemNames.add("4"); + ChannelElemNames.add("5"); + ChannelElemNames.add("6"); + ChannelElemNames.add("7"); + fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 2000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ManualControlCommand obj = new ManualControlCommand(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ManualControlCommand GetInstance(UAVObjectManager objMngr, int instID) + { + return (ManualControlCommand)(objMngr.getObject(ManualControlCommand.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x926794; + protected static final String NAME = "ManualControlCommand"; + protected static String DESCRIPTION = "The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java new file mode 100644 index 000000000..c14aef758 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -0,0 +1,395 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings to indicate how to decode receiver input by @ref ManualControlModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings to indicate how to decode receiver input by @ref ManualControlModule. + +generated from manualcontrolsettings.xml + **/ +public class ManualControlSettings extends UAVDataObject { + + public ManualControlSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List InputModeElemNames = new ArrayList(); + InputModeElemNames.add("0"); + List InputModeEnumOptions = new ArrayList(); + InputModeEnumOptions.add("PWM"); + InputModeEnumOptions.add("PPM"); + InputModeEnumOptions.add("Spektrum"); + fields.add( new UAVObjectField("InputMode", "", UAVObjectField.FieldType.ENUM, InputModeElemNames, InputModeEnumOptions) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + List RollEnumOptions = new ArrayList(); + RollEnumOptions.add("Channel1"); + RollEnumOptions.add("Channel2"); + RollEnumOptions.add("Channel3"); + RollEnumOptions.add("Channel4"); + RollEnumOptions.add("Channel5"); + RollEnumOptions.add("Channel6"); + RollEnumOptions.add("Channel7"); + RollEnumOptions.add("Channel8"); + RollEnumOptions.add("None"); + fields.add( new UAVObjectField("Roll", "channel", UAVObjectField.FieldType.ENUM, RollElemNames, RollEnumOptions) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + List PitchEnumOptions = new ArrayList(); + PitchEnumOptions.add("Channel1"); + PitchEnumOptions.add("Channel2"); + PitchEnumOptions.add("Channel3"); + PitchEnumOptions.add("Channel4"); + PitchEnumOptions.add("Channel5"); + PitchEnumOptions.add("Channel6"); + PitchEnumOptions.add("Channel7"); + PitchEnumOptions.add("Channel8"); + PitchEnumOptions.add("None"); + fields.add( new UAVObjectField("Pitch", "channel", UAVObjectField.FieldType.ENUM, PitchElemNames, PitchEnumOptions) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + List YawEnumOptions = new ArrayList(); + YawEnumOptions.add("Channel1"); + YawEnumOptions.add("Channel2"); + YawEnumOptions.add("Channel3"); + YawEnumOptions.add("Channel4"); + YawEnumOptions.add("Channel5"); + YawEnumOptions.add("Channel6"); + YawEnumOptions.add("Channel7"); + YawEnumOptions.add("Channel8"); + YawEnumOptions.add("None"); + fields.add( new UAVObjectField("Yaw", "channel", UAVObjectField.FieldType.ENUM, YawElemNames, YawEnumOptions) ); + + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + List ThrottleEnumOptions = new ArrayList(); + ThrottleEnumOptions.add("Channel1"); + ThrottleEnumOptions.add("Channel2"); + ThrottleEnumOptions.add("Channel3"); + ThrottleEnumOptions.add("Channel4"); + ThrottleEnumOptions.add("Channel5"); + ThrottleEnumOptions.add("Channel6"); + ThrottleEnumOptions.add("Channel7"); + ThrottleEnumOptions.add("Channel8"); + ThrottleEnumOptions.add("None"); + fields.add( new UAVObjectField("Throttle", "channel", UAVObjectField.FieldType.ENUM, ThrottleElemNames, ThrottleEnumOptions) ); + + List FlightModeElemNames = new ArrayList(); + FlightModeElemNames.add("0"); + List FlightModeEnumOptions = new ArrayList(); + FlightModeEnumOptions.add("Channel1"); + FlightModeEnumOptions.add("Channel2"); + FlightModeEnumOptions.add("Channel3"); + FlightModeEnumOptions.add("Channel4"); + FlightModeEnumOptions.add("Channel5"); + FlightModeEnumOptions.add("Channel6"); + FlightModeEnumOptions.add("Channel7"); + FlightModeEnumOptions.add("Channel8"); + FlightModeEnumOptions.add("None"); + fields.add( new UAVObjectField("FlightMode", "channel", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); + + List Accessory1ElemNames = new ArrayList(); + Accessory1ElemNames.add("0"); + List Accessory1EnumOptions = new ArrayList(); + Accessory1EnumOptions.add("Channel1"); + Accessory1EnumOptions.add("Channel2"); + Accessory1EnumOptions.add("Channel3"); + Accessory1EnumOptions.add("Channel4"); + Accessory1EnumOptions.add("Channel5"); + Accessory1EnumOptions.add("Channel6"); + Accessory1EnumOptions.add("Channel7"); + Accessory1EnumOptions.add("Channel8"); + Accessory1EnumOptions.add("None"); + fields.add( new UAVObjectField("Accessory1", "channel", UAVObjectField.FieldType.ENUM, Accessory1ElemNames, Accessory1EnumOptions) ); + + List Accessory2ElemNames = new ArrayList(); + Accessory2ElemNames.add("0"); + List Accessory2EnumOptions = new ArrayList(); + Accessory2EnumOptions.add("Channel1"); + Accessory2EnumOptions.add("Channel2"); + Accessory2EnumOptions.add("Channel3"); + Accessory2EnumOptions.add("Channel4"); + Accessory2EnumOptions.add("Channel5"); + Accessory2EnumOptions.add("Channel6"); + Accessory2EnumOptions.add("Channel7"); + Accessory2EnumOptions.add("Channel8"); + Accessory2EnumOptions.add("None"); + fields.add( new UAVObjectField("Accessory2", "channel", UAVObjectField.FieldType.ENUM, Accessory2ElemNames, Accessory2EnumOptions) ); + + List Accessory3ElemNames = new ArrayList(); + Accessory3ElemNames.add("0"); + List Accessory3EnumOptions = new ArrayList(); + Accessory3EnumOptions.add("Channel1"); + Accessory3EnumOptions.add("Channel2"); + Accessory3EnumOptions.add("Channel3"); + Accessory3EnumOptions.add("Channel4"); + Accessory3EnumOptions.add("Channel5"); + Accessory3EnumOptions.add("Channel6"); + Accessory3EnumOptions.add("Channel7"); + Accessory3EnumOptions.add("Channel8"); + Accessory3EnumOptions.add("None"); + fields.add( new UAVObjectField("Accessory3", "channel", UAVObjectField.FieldType.ENUM, Accessory3ElemNames, Accessory3EnumOptions) ); + + List ArmingElemNames = new ArrayList(); + ArmingElemNames.add("0"); + List ArmingEnumOptions = new ArrayList(); + ArmingEnumOptions.add("Always Disarmed"); + ArmingEnumOptions.add("Always Armed"); + ArmingEnumOptions.add("Roll Left"); + ArmingEnumOptions.add("Roll Right"); + ArmingEnumOptions.add("Pitch Forward"); + ArmingEnumOptions.add("Pitch Aft"); + ArmingEnumOptions.add("Yaw Left"); + ArmingEnumOptions.add("Yaw Right"); + fields.add( new UAVObjectField("Arming", "", UAVObjectField.FieldType.ENUM, ArmingElemNames, ArmingEnumOptions) ); + + List Stabilization1SettingsElemNames = new ArrayList(); + Stabilization1SettingsElemNames.add("Roll"); + Stabilization1SettingsElemNames.add("Pitch"); + Stabilization1SettingsElemNames.add("Yaw"); + List Stabilization1SettingsEnumOptions = new ArrayList(); + Stabilization1SettingsEnumOptions.add("None"); + Stabilization1SettingsEnumOptions.add("Rate"); + Stabilization1SettingsEnumOptions.add("Attitude"); + fields.add( new UAVObjectField("Stabilization1Settings", "", UAVObjectField.FieldType.ENUM, Stabilization1SettingsElemNames, Stabilization1SettingsEnumOptions) ); + + List Stabilization2SettingsElemNames = new ArrayList(); + Stabilization2SettingsElemNames.add("Roll"); + Stabilization2SettingsElemNames.add("Pitch"); + Stabilization2SettingsElemNames.add("Yaw"); + List Stabilization2SettingsEnumOptions = new ArrayList(); + Stabilization2SettingsEnumOptions.add("None"); + Stabilization2SettingsEnumOptions.add("Rate"); + Stabilization2SettingsEnumOptions.add("Attitude"); + fields.add( new UAVObjectField("Stabilization2Settings", "", UAVObjectField.FieldType.ENUM, Stabilization2SettingsElemNames, Stabilization2SettingsEnumOptions) ); + + List Stabilization3SettingsElemNames = new ArrayList(); + Stabilization3SettingsElemNames.add("Roll"); + Stabilization3SettingsElemNames.add("Pitch"); + Stabilization3SettingsElemNames.add("Yaw"); + List Stabilization3SettingsEnumOptions = new ArrayList(); + Stabilization3SettingsEnumOptions.add("None"); + Stabilization3SettingsEnumOptions.add("Rate"); + Stabilization3SettingsEnumOptions.add("Attitude"); + fields.add( new UAVObjectField("Stabilization3Settings", "", UAVObjectField.FieldType.ENUM, Stabilization3SettingsElemNames, Stabilization3SettingsEnumOptions) ); + + List FlightModePositionElemNames = new ArrayList(); + FlightModePositionElemNames.add("0"); + FlightModePositionElemNames.add("1"); + FlightModePositionElemNames.add("2"); + List FlightModePositionEnumOptions = new ArrayList(); + FlightModePositionEnumOptions.add("Manual"); + FlightModePositionEnumOptions.add("Stabilized1"); + FlightModePositionEnumOptions.add("Stabilized2"); + FlightModePositionEnumOptions.add("Stabilized3"); + FlightModePositionEnumOptions.add("VelocityControl"); + FlightModePositionEnumOptions.add("PositionHold"); + fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); + + List ChannelMaxElemNames = new ArrayList(); + ChannelMaxElemNames.add("0"); + ChannelMaxElemNames.add("1"); + ChannelMaxElemNames.add("2"); + ChannelMaxElemNames.add("3"); + ChannelMaxElemNames.add("4"); + ChannelMaxElemNames.add("5"); + ChannelMaxElemNames.add("6"); + ChannelMaxElemNames.add("7"); + fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); + + List ChannelNeutralElemNames = new ArrayList(); + ChannelNeutralElemNames.add("0"); + ChannelNeutralElemNames.add("1"); + ChannelNeutralElemNames.add("2"); + ChannelNeutralElemNames.add("3"); + ChannelNeutralElemNames.add("4"); + ChannelNeutralElemNames.add("5"); + ChannelNeutralElemNames.add("6"); + ChannelNeutralElemNames.add("7"); + fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); + + List ChannelMinElemNames = new ArrayList(); + ChannelMinElemNames.add("0"); + ChannelMinElemNames.add("1"); + ChannelMinElemNames.add("2"); + ChannelMinElemNames.add("3"); + ChannelMinElemNames.add("4"); + ChannelMinElemNames.add("5"); + ChannelMinElemNames.add("6"); + ChannelMinElemNames.add("7"); + fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); + + List ArmedTimeoutElemNames = new ArrayList(); + ArmedTimeoutElemNames.add("0"); + fields.add( new UAVObjectField("ArmedTimeout", "ms", UAVObjectField.FieldType.UINT16, ArmedTimeoutElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("InputMode").setValue(0); + getField("Roll").setValue(0); + getField("Pitch").setValue(1); + getField("Yaw").setValue(2); + getField("Throttle").setValue(3); + getField("FlightMode").setValue(4); + getField("Accessory1").setValue(8); + getField("Accessory2").setValue(8); + getField("Accessory3").setValue(8); + getField("Arming").setValue(0); + getField("Stabilization1Settings").setValue(2,0); + getField("Stabilization1Settings").setValue(2,1); + getField("Stabilization1Settings").setValue(2,2); + getField("Stabilization2Settings").setValue(2,0); + getField("Stabilization2Settings").setValue(2,1); + getField("Stabilization2Settings").setValue(2,2); + getField("Stabilization3Settings").setValue(2,0); + getField("Stabilization3Settings").setValue(2,1); + getField("Stabilization3Settings").setValue(2,2); + getField("FlightModePosition").setValue(0,0); + getField("FlightModePosition").setValue(1,1); + getField("FlightModePosition").setValue(2,2); + getField("ChannelMax").setValue(2000,0); + getField("ChannelMax").setValue(2000,1); + getField("ChannelMax").setValue(2000,2); + getField("ChannelMax").setValue(2000,3); + getField("ChannelMax").setValue(2000,4); + getField("ChannelMax").setValue(2000,5); + getField("ChannelMax").setValue(2000,6); + getField("ChannelMax").setValue(2000,7); + getField("ChannelNeutral").setValue(1500,0); + getField("ChannelNeutral").setValue(1500,1); + getField("ChannelNeutral").setValue(1500,2); + getField("ChannelNeutral").setValue(1500,3); + getField("ChannelNeutral").setValue(1500,4); + getField("ChannelNeutral").setValue(1500,5); + getField("ChannelNeutral").setValue(1500,6); + getField("ChannelNeutral").setValue(1500,7); + getField("ChannelMin").setValue(1000,0); + getField("ChannelMin").setValue(1000,1); + getField("ChannelMin").setValue(1000,2); + getField("ChannelMin").setValue(1000,3); + getField("ChannelMin").setValue(1000,4); + getField("ChannelMin").setValue(1000,5); + getField("ChannelMin").setValue(1000,6); + getField("ChannelMin").setValue(1000,7); + getField("ArmedTimeout").setValue(30000); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ManualControlSettings obj = new ManualControlSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ManualControlSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (ManualControlSettings)(objMngr.getObject(ManualControlSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x2B82102; + protected static final String NAME = "ManualControlSettings"; + protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java new file mode 100644 index 000000000..554e366f3 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java @@ -0,0 +1,357 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + +generated from mixersettings.xml + **/ +public class MixerSettings extends UAVDataObject { + + public MixerSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List MaxAccelElemNames = new ArrayList(); + MaxAccelElemNames.add("0"); + fields.add( new UAVObjectField("MaxAccel", "units/sec", UAVObjectField.FieldType.FLOAT32, MaxAccelElemNames, null) ); + + List FeedForwardElemNames = new ArrayList(); + FeedForwardElemNames.add("0"); + fields.add( new UAVObjectField("FeedForward", "", UAVObjectField.FieldType.FLOAT32, FeedForwardElemNames, null) ); + + List AccelTimeElemNames = new ArrayList(); + AccelTimeElemNames.add("0"); + fields.add( new UAVObjectField("AccelTime", "ms", UAVObjectField.FieldType.FLOAT32, AccelTimeElemNames, null) ); + + List DecelTimeElemNames = new ArrayList(); + DecelTimeElemNames.add("0"); + fields.add( new UAVObjectField("DecelTime", "ms", UAVObjectField.FieldType.FLOAT32, DecelTimeElemNames, null) ); + + List ThrottleCurve1ElemNames = new ArrayList(); + ThrottleCurve1ElemNames.add("0"); + ThrottleCurve1ElemNames.add("25"); + ThrottleCurve1ElemNames.add("50"); + ThrottleCurve1ElemNames.add("75"); + ThrottleCurve1ElemNames.add("100"); + fields.add( new UAVObjectField("ThrottleCurve1", "percent", UAVObjectField.FieldType.FLOAT32, ThrottleCurve1ElemNames, null) ); + + List ThrottleCurve2ElemNames = new ArrayList(); + ThrottleCurve2ElemNames.add("0"); + ThrottleCurve2ElemNames.add("25"); + ThrottleCurve2ElemNames.add("50"); + ThrottleCurve2ElemNames.add("75"); + ThrottleCurve2ElemNames.add("100"); + fields.add( new UAVObjectField("ThrottleCurve2", "percent", UAVObjectField.FieldType.FLOAT32, ThrottleCurve2ElemNames, null) ); + + List Mixer1TypeElemNames = new ArrayList(); + Mixer1TypeElemNames.add("0"); + List Mixer1TypeEnumOptions = new ArrayList(); + Mixer1TypeEnumOptions.add("Disabled"); + Mixer1TypeEnumOptions.add("Motor"); + Mixer1TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer1Type", "", UAVObjectField.FieldType.ENUM, Mixer1TypeElemNames, Mixer1TypeEnumOptions) ); + + List Mixer1VectorElemNames = new ArrayList(); + Mixer1VectorElemNames.add("ThrottleCurve1"); + Mixer1VectorElemNames.add("ThrottleCurve2"); + Mixer1VectorElemNames.add("Roll"); + Mixer1VectorElemNames.add("Pitch"); + Mixer1VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer1Vector", "", UAVObjectField.FieldType.INT8, Mixer1VectorElemNames, null) ); + + List Mixer2TypeElemNames = new ArrayList(); + Mixer2TypeElemNames.add("0"); + List Mixer2TypeEnumOptions = new ArrayList(); + Mixer2TypeEnumOptions.add("Disabled"); + Mixer2TypeEnumOptions.add("Motor"); + Mixer2TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer2Type", "", UAVObjectField.FieldType.ENUM, Mixer2TypeElemNames, Mixer2TypeEnumOptions) ); + + List Mixer2VectorElemNames = new ArrayList(); + Mixer2VectorElemNames.add("ThrottleCurve1"); + Mixer2VectorElemNames.add("ThrottleCurve2"); + Mixer2VectorElemNames.add("Roll"); + Mixer2VectorElemNames.add("Pitch"); + Mixer2VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer2Vector", "", UAVObjectField.FieldType.INT8, Mixer2VectorElemNames, null) ); + + List Mixer3TypeElemNames = new ArrayList(); + Mixer3TypeElemNames.add("0"); + List Mixer3TypeEnumOptions = new ArrayList(); + Mixer3TypeEnumOptions.add("Disabled"); + Mixer3TypeEnumOptions.add("Motor"); + Mixer3TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer3Type", "", UAVObjectField.FieldType.ENUM, Mixer3TypeElemNames, Mixer3TypeEnumOptions) ); + + List Mixer3VectorElemNames = new ArrayList(); + Mixer3VectorElemNames.add("ThrottleCurve1"); + Mixer3VectorElemNames.add("ThrottleCurve2"); + Mixer3VectorElemNames.add("Roll"); + Mixer3VectorElemNames.add("Pitch"); + Mixer3VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer3Vector", "", UAVObjectField.FieldType.INT8, Mixer3VectorElemNames, null) ); + + List Mixer4TypeElemNames = new ArrayList(); + Mixer4TypeElemNames.add("0"); + List Mixer4TypeEnumOptions = new ArrayList(); + Mixer4TypeEnumOptions.add("Disabled"); + Mixer4TypeEnumOptions.add("Motor"); + Mixer4TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer4Type", "", UAVObjectField.FieldType.ENUM, Mixer4TypeElemNames, Mixer4TypeEnumOptions) ); + + List Mixer4VectorElemNames = new ArrayList(); + Mixer4VectorElemNames.add("ThrottleCurve1"); + Mixer4VectorElemNames.add("ThrottleCurve2"); + Mixer4VectorElemNames.add("Roll"); + Mixer4VectorElemNames.add("Pitch"); + Mixer4VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer4Vector", "", UAVObjectField.FieldType.INT8, Mixer4VectorElemNames, null) ); + + List Mixer5TypeElemNames = new ArrayList(); + Mixer5TypeElemNames.add("0"); + List Mixer5TypeEnumOptions = new ArrayList(); + Mixer5TypeEnumOptions.add("Disabled"); + Mixer5TypeEnumOptions.add("Motor"); + Mixer5TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer5Type", "", UAVObjectField.FieldType.ENUM, Mixer5TypeElemNames, Mixer5TypeEnumOptions) ); + + List Mixer5VectorElemNames = new ArrayList(); + Mixer5VectorElemNames.add("ThrottleCurve1"); + Mixer5VectorElemNames.add("ThrottleCurve2"); + Mixer5VectorElemNames.add("Roll"); + Mixer5VectorElemNames.add("Pitch"); + Mixer5VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer5Vector", "", UAVObjectField.FieldType.INT8, Mixer5VectorElemNames, null) ); + + List Mixer6TypeElemNames = new ArrayList(); + Mixer6TypeElemNames.add("0"); + List Mixer6TypeEnumOptions = new ArrayList(); + Mixer6TypeEnumOptions.add("Disabled"); + Mixer6TypeEnumOptions.add("Motor"); + Mixer6TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer6Type", "", UAVObjectField.FieldType.ENUM, Mixer6TypeElemNames, Mixer6TypeEnumOptions) ); + + List Mixer6VectorElemNames = new ArrayList(); + Mixer6VectorElemNames.add("ThrottleCurve1"); + Mixer6VectorElemNames.add("ThrottleCurve2"); + Mixer6VectorElemNames.add("Roll"); + Mixer6VectorElemNames.add("Pitch"); + Mixer6VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer6Vector", "", UAVObjectField.FieldType.INT8, Mixer6VectorElemNames, null) ); + + List Mixer7TypeElemNames = new ArrayList(); + Mixer7TypeElemNames.add("0"); + List Mixer7TypeEnumOptions = new ArrayList(); + Mixer7TypeEnumOptions.add("Disabled"); + Mixer7TypeEnumOptions.add("Motor"); + Mixer7TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer7Type", "", UAVObjectField.FieldType.ENUM, Mixer7TypeElemNames, Mixer7TypeEnumOptions) ); + + List Mixer7VectorElemNames = new ArrayList(); + Mixer7VectorElemNames.add("ThrottleCurve1"); + Mixer7VectorElemNames.add("ThrottleCurve2"); + Mixer7VectorElemNames.add("Roll"); + Mixer7VectorElemNames.add("Pitch"); + Mixer7VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer7Vector", "", UAVObjectField.FieldType.INT8, Mixer7VectorElemNames, null) ); + + List Mixer8TypeElemNames = new ArrayList(); + Mixer8TypeElemNames.add("0"); + List Mixer8TypeEnumOptions = new ArrayList(); + Mixer8TypeEnumOptions.add("Disabled"); + Mixer8TypeEnumOptions.add("Motor"); + Mixer8TypeEnumOptions.add("Servo"); + fields.add( new UAVObjectField("Mixer8Type", "", UAVObjectField.FieldType.ENUM, Mixer8TypeElemNames, Mixer8TypeEnumOptions) ); + + List Mixer8VectorElemNames = new ArrayList(); + Mixer8VectorElemNames.add("ThrottleCurve1"); + Mixer8VectorElemNames.add("ThrottleCurve2"); + Mixer8VectorElemNames.add("Roll"); + Mixer8VectorElemNames.add("Pitch"); + Mixer8VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer8Vector", "", UAVObjectField.FieldType.INT8, Mixer8VectorElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("MaxAccel").setValue(1000); + getField("FeedForward").setValue(0); + getField("AccelTime").setValue(0); + getField("DecelTime").setValue(0); + getField("ThrottleCurve1").setValue(0,0); + getField("ThrottleCurve1").setValue(0.25,1); + getField("ThrottleCurve1").setValue(0.5,2); + getField("ThrottleCurve1").setValue(0.75,3); + getField("ThrottleCurve1").setValue(1,4); + getField("ThrottleCurve2").setValue(0,0); + getField("ThrottleCurve2").setValue(0.25,1); + getField("ThrottleCurve2").setValue(0.5,2); + getField("ThrottleCurve2").setValue(0.75,3); + getField("ThrottleCurve2").setValue(1,4); + getField("Mixer1Type").setValue(0); + getField("Mixer1Vector").setValue(0,0); + getField("Mixer1Vector").setValue(0,1); + getField("Mixer1Vector").setValue(0,2); + getField("Mixer1Vector").setValue(0,3); + getField("Mixer1Vector").setValue(0,4); + getField("Mixer2Type").setValue(0); + getField("Mixer2Vector").setValue(0,0); + getField("Mixer2Vector").setValue(0,1); + getField("Mixer2Vector").setValue(0,2); + getField("Mixer2Vector").setValue(0,3); + getField("Mixer2Vector").setValue(0,4); + getField("Mixer3Type").setValue(0); + getField("Mixer3Vector").setValue(0,0); + getField("Mixer3Vector").setValue(0,1); + getField("Mixer3Vector").setValue(0,2); + getField("Mixer3Vector").setValue(0,3); + getField("Mixer3Vector").setValue(0,4); + getField("Mixer4Type").setValue(0); + getField("Mixer4Vector").setValue(0,0); + getField("Mixer4Vector").setValue(0,1); + getField("Mixer4Vector").setValue(0,2); + getField("Mixer4Vector").setValue(0,3); + getField("Mixer4Vector").setValue(0,4); + getField("Mixer5Type").setValue(0); + getField("Mixer5Vector").setValue(0,0); + getField("Mixer5Vector").setValue(0,1); + getField("Mixer5Vector").setValue(0,2); + getField("Mixer5Vector").setValue(0,3); + getField("Mixer5Vector").setValue(0,4); + getField("Mixer6Type").setValue(0); + getField("Mixer6Vector").setValue(0,0); + getField("Mixer6Vector").setValue(0,1); + getField("Mixer6Vector").setValue(0,2); + getField("Mixer6Vector").setValue(0,3); + getField("Mixer6Vector").setValue(0,4); + getField("Mixer7Type").setValue(0); + getField("Mixer7Vector").setValue(0,0); + getField("Mixer7Vector").setValue(0,1); + getField("Mixer7Vector").setValue(0,2); + getField("Mixer7Vector").setValue(0,3); + getField("Mixer7Vector").setValue(0,4); + getField("Mixer8Type").setValue(0); + getField("Mixer8Vector").setValue(0,0); + getField("Mixer8Vector").setValue(0,1); + getField("Mixer8Vector").setValue(0,2); + getField("Mixer8Vector").setValue(0,3); + getField("Mixer8Vector").setValue(0,4); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + MixerSettings obj = new MixerSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public MixerSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (MixerSettings)(objMngr.getObject(MixerSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x4FAE374E; + protected static final String NAME = "MixerSettings"; + protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java new file mode 100644 index 000000000..fbd405b40 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java @@ -0,0 +1,167 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Status for the matrix mixer showing the output of each mixer after all scaling + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Status for the matrix mixer showing the output of each mixer after all scaling + +generated from mixerstatus.xml + **/ +public class MixerStatus extends UAVDataObject { + + public MixerStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List Mixer1ElemNames = new ArrayList(); + Mixer1ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer1", "", UAVObjectField.FieldType.FLOAT32, Mixer1ElemNames, null) ); + + List Mixer2ElemNames = new ArrayList(); + Mixer2ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer2", "", UAVObjectField.FieldType.FLOAT32, Mixer2ElemNames, null) ); + + List Mixer3ElemNames = new ArrayList(); + Mixer3ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer3", "", UAVObjectField.FieldType.FLOAT32, Mixer3ElemNames, null) ); + + List Mixer4ElemNames = new ArrayList(); + Mixer4ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer4", "", UAVObjectField.FieldType.FLOAT32, Mixer4ElemNames, null) ); + + List Mixer5ElemNames = new ArrayList(); + Mixer5ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer5", "", UAVObjectField.FieldType.FLOAT32, Mixer5ElemNames, null) ); + + List Mixer6ElemNames = new ArrayList(); + Mixer6ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer6", "", UAVObjectField.FieldType.FLOAT32, Mixer6ElemNames, null) ); + + List Mixer7ElemNames = new ArrayList(); + Mixer7ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer7", "", UAVObjectField.FieldType.FLOAT32, Mixer7ElemNames, null) ); + + List Mixer8ElemNames = new ArrayList(); + Mixer8ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer8", "", UAVObjectField.FieldType.FLOAT32, Mixer8ElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + MixerStatus obj = new MixerStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public MixerStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (MixerStatus)(objMngr.getObject(MixerStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xF6A33F10; + protected static final String NAME = "MixerStatus"; + protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java new file mode 100644 index 000000000..f16ddd199 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The projection of acceleration in the NED reference frame used by @ref Guidance. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The projection of acceleration in the NED reference frame used by @ref Guidance. + +generated from nedaccel.xml + **/ +public class NedAccel extends UAVDataObject { + + public NedAccel() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm/s^2", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm/s^2", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm/s^2", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10001; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + NedAccel obj = new NedAccel(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public NedAccel GetInstance(UAVObjectManager objMngr, int instID) + { + return (NedAccel)(objMngr.getObject(NedAccel.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x8E852CE8; + protected static final String NAME = "NedAccel"; + protected static String DESCRIPTION = "The projection of acceleration in the NED reference frame used by @ref Guidance."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java new file mode 100644 index 000000000..2a09c2b40 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java @@ -0,0 +1,160 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Someone who knows please enter this + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Someone who knows please enter this + +generated from objectpersistence.xml + **/ +public class ObjectPersistence extends UAVDataObject { + + public ObjectPersistence() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List OperationElemNames = new ArrayList(); + OperationElemNames.add("0"); + List OperationEnumOptions = new ArrayList(); + OperationEnumOptions.add("Load"); + OperationEnumOptions.add("Save"); + OperationEnumOptions.add("Delete"); + fields.add( new UAVObjectField("Operation", "", UAVObjectField.FieldType.ENUM, OperationElemNames, OperationEnumOptions) ); + + List SelectionElemNames = new ArrayList(); + SelectionElemNames.add("0"); + List SelectionEnumOptions = new ArrayList(); + SelectionEnumOptions.add("SingleObject"); + SelectionEnumOptions.add("AllSettings"); + SelectionEnumOptions.add("AllMetaObjects"); + SelectionEnumOptions.add("AllObjects"); + fields.add( new UAVObjectField("Selection", "", UAVObjectField.FieldType.ENUM, SelectionElemNames, SelectionEnumOptions) ); + + List ObjectIDElemNames = new ArrayList(); + ObjectIDElemNames.add("0"); + fields.add( new UAVObjectField("ObjectID", "", UAVObjectField.FieldType.UINT32, ObjectIDElemNames, null) ); + + List InstanceIDElemNames = new ArrayList(); + InstanceIDElemNames.add("0"); + fields.add( new UAVObjectField("InstanceID", "", UAVObjectField.FieldType.UINT32, InstanceIDElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + ObjectPersistence obj = new ObjectPersistence(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public ObjectPersistence GetInstance(UAVObjectManager objMngr, int instID) + { + return (ObjectPersistence)(objMngr.getObject(ObjectPersistence.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x22216832; + protected static final String NAME = "ObjectPersistence"; + protected static String DESCRIPTION = "Someone who knows please enter this"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java new file mode 100644 index 000000000..444009f90 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the current position relative to @ref HomeLocation + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the current position relative to @ref HomeLocation + +generated from positionactual.xml + **/ +public class PositionActual extends UAVDataObject { + + public PositionActual() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PositionActual obj = new PositionActual(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PositionActual GetInstance(UAVObjectManager objMngr, int instID) + { + return (PositionActual)(objMngr.getObject(PositionActual.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE0739636; + protected static final String NAME = "PositionActual"; + protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java new file mode 100644 index 000000000..5cf51df71 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner + +generated from positiondesired.xml + **/ +public class PositionDesired extends UAVDataObject { + + public PositionDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PositionDesired obj = new PositionDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PositionDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (PositionDesired)(objMngr.getObject(PositionDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x2FC4E5BA; + protected static final String NAME = "PositionDesired"; + protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java new file mode 100644 index 000000000..7164c0957 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Status for the matrix mixer showing the output of each mixer after all scaling + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Status for the matrix mixer showing the output of each mixer after all scaling + +generated from ratedesired.xml + **/ +public class RateDesired extends UAVDataObject { + + public RateDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "deg/s", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "deg/s", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "deg/s", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + RateDesired obj = new RateDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public RateDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (RateDesired)(objMngr.getObject(RateDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xBA41B51C; + protected static final String NAME = "RateDesired"; + protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java new file mode 100644 index 000000000..4e9f0b8b8 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java @@ -0,0 +1,139 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The raw data from the ultrasound sonar sensor with altitude estimate. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The raw data from the ultrasound sonar sensor with altitude estimate. + +generated from sonaraltitude.xml + **/ +public class SonarAltitude extends UAVDataObject { + + public SonarAltitude() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + SonarAltitude obj = new SonarAltitude(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public SonarAltitude GetInstance(UAVObjectManager objMngr, int instID) + { + return (SonarAltitude)(objMngr.getObject(SonarAltitude.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1FDD844C; + protected static final String NAME = "SonarAltitude"; + protected static String DESCRIPTION = "The raw data from the ultrasound sonar sensor with altitude estimate."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java new file mode 100644 index 000000000..8cba8a54c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java @@ -0,0 +1,161 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule. + +generated from stabilizationdesired.xml + **/ +public class StabilizationDesired extends UAVDataObject { + + public StabilizationDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "degrees", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "degrees", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "degrees", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); + + List StabilizationModeElemNames = new ArrayList(); + StabilizationModeElemNames.add("Roll"); + StabilizationModeElemNames.add("Pitch"); + StabilizationModeElemNames.add("Yaw"); + List StabilizationModeEnumOptions = new ArrayList(); + StabilizationModeEnumOptions.add("None"); + StabilizationModeEnumOptions.add("Rate"); + StabilizationModeEnumOptions.add("Attitude"); + fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + StabilizationDesired obj = new StabilizationDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public StabilizationDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (StabilizationDesired)(objMngr.getObject(StabilizationDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x41AA9DC2; + protected static final String NAME = "StabilizationDesired"; + protected static String DESCRIPTION = "The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java new file mode 100644 index 000000000..74c480e1c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java @@ -0,0 +1,222 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired + +generated from stabilizationsettings.xml + **/ +public class StabilizationSettings extends UAVDataObject { + + public StabilizationSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollMaxElemNames = new ArrayList(); + RollMaxElemNames.add("0"); + fields.add( new UAVObjectField("RollMax", "degrees", UAVObjectField.FieldType.UINT8, RollMaxElemNames, null) ); + + List PitchMaxElemNames = new ArrayList(); + PitchMaxElemNames.add("0"); + fields.add( new UAVObjectField("PitchMax", "degrees", UAVObjectField.FieldType.UINT8, PitchMaxElemNames, null) ); + + List YawMaxElemNames = new ArrayList(); + YawMaxElemNames.add("0"); + fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); + + List ManualRateElemNames = new ArrayList(); + ManualRateElemNames.add("Roll"); + ManualRateElemNames.add("Pitch"); + ManualRateElemNames.add("Yaw"); + fields.add( new UAVObjectField("ManualRate", "degrees/sec", UAVObjectField.FieldType.FLOAT32, ManualRateElemNames, null) ); + + List MaximumRateElemNames = new ArrayList(); + MaximumRateElemNames.add("Roll"); + MaximumRateElemNames.add("Pitch"); + MaximumRateElemNames.add("Yaw"); + fields.add( new UAVObjectField("MaximumRate", "degrees/sec", UAVObjectField.FieldType.FLOAT32, MaximumRateElemNames, null) ); + + List RollRatePIElemNames = new ArrayList(); + RollRatePIElemNames.add("Kp"); + RollRatePIElemNames.add("Ki"); + RollRatePIElemNames.add("ILimit"); + fields.add( new UAVObjectField("RollRatePI", "", UAVObjectField.FieldType.FLOAT32, RollRatePIElemNames, null) ); + + List PitchRatePIElemNames = new ArrayList(); + PitchRatePIElemNames.add("Kp"); + PitchRatePIElemNames.add("Ki"); + PitchRatePIElemNames.add("ILimit"); + fields.add( new UAVObjectField("PitchRatePI", "", UAVObjectField.FieldType.FLOAT32, PitchRatePIElemNames, null) ); + + List YawRatePIElemNames = new ArrayList(); + YawRatePIElemNames.add("Kp"); + YawRatePIElemNames.add("Ki"); + YawRatePIElemNames.add("ILimit"); + fields.add( new UAVObjectField("YawRatePI", "", UAVObjectField.FieldType.FLOAT32, YawRatePIElemNames, null) ); + + List RollPIElemNames = new ArrayList(); + RollPIElemNames.add("Kp"); + RollPIElemNames.add("Ki"); + RollPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("RollPI", "", UAVObjectField.FieldType.FLOAT32, RollPIElemNames, null) ); + + List PitchPIElemNames = new ArrayList(); + PitchPIElemNames.add("Kp"); + PitchPIElemNames.add("Ki"); + PitchPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("PitchPI", "", UAVObjectField.FieldType.FLOAT32, PitchPIElemNames, null) ); + + List YawPIElemNames = new ArrayList(); + YawPIElemNames.add("Kp"); + YawPIElemNames.add("Ki"); + YawPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("YawPI", "", UAVObjectField.FieldType.FLOAT32, YawPIElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("RollMax").setValue(35); + getField("PitchMax").setValue(35); + getField("YawMax").setValue(35); + getField("ManualRate").setValue(150,0); + getField("ManualRate").setValue(150,1); + getField("ManualRate").setValue(150,2); + getField("MaximumRate").setValue(300,0); + getField("MaximumRate").setValue(300,1); + getField("MaximumRate").setValue(300,2); + getField("RollRatePI").setValue(0.0015,0); + getField("RollRatePI").setValue(0,1); + getField("RollRatePI").setValue(0.3,2); + getField("PitchRatePI").setValue(0.0015,0); + getField("PitchRatePI").setValue(0,1); + getField("PitchRatePI").setValue(0.3,2); + getField("YawRatePI").setValue(0.003,0); + getField("YawRatePI").setValue(0,1); + getField("YawRatePI").setValue(0.3,2); + getField("RollPI").setValue(2,0); + getField("RollPI").setValue(0,1); + getField("RollPI").setValue(50,2); + getField("PitchPI").setValue(2,0); + getField("PitchPI").setValue(0,1); + getField("PitchPI").setValue(50,2); + getField("YawPI").setValue(2,0); + getField("YawPI").setValue(0,1); + getField("YawPI").setValue(50,2); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + StabilizationSettings obj = new StabilizationSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public StabilizationSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (StabilizationSettings)(objMngr.getObject(StabilizationSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE2147404; + protected static final String NAME = "StabilizationSettings"; + protected static String DESCRIPTION = "PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java new file mode 100644 index 000000000..9136627f4 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -0,0 +1,176 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. + +generated from systemalarms.xml + **/ +public class SystemAlarms extends UAVDataObject { + + public SystemAlarms() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AlarmElemNames = new ArrayList(); + AlarmElemNames.add("OutOfMemory"); + AlarmElemNames.add("StackOverflow"); + AlarmElemNames.add("CPUOverload"); + AlarmElemNames.add("EventSystem"); + AlarmElemNames.add("SDCard"); + AlarmElemNames.add("Telemetry"); + AlarmElemNames.add("ManualControl"); + AlarmElemNames.add("Actuator"); + AlarmElemNames.add("Attitude"); + AlarmElemNames.add("Stabilization"); + AlarmElemNames.add("Guidance"); + AlarmElemNames.add("AHRSComms"); + AlarmElemNames.add("Battery"); + AlarmElemNames.add("FlightTime"); + AlarmElemNames.add("I2C"); + AlarmElemNames.add("GPS"); + List AlarmEnumOptions = new ArrayList(); + AlarmEnumOptions.add("Uninitialised"); + AlarmEnumOptions.add("OK"); + AlarmEnumOptions.add("Warning"); + AlarmEnumOptions.add("Error"); + AlarmEnumOptions.add("Critical"); + fields.add( new UAVObjectField("Alarm", "", UAVObjectField.FieldType.ENUM, AlarmElemNames, AlarmEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 4000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Alarm").setValue(0,0); + getField("Alarm").setValue(0,1); + getField("Alarm").setValue(0,2); + getField("Alarm").setValue(0,3); + getField("Alarm").setValue(0,4); + getField("Alarm").setValue(0,5); + getField("Alarm").setValue(0,6); + getField("Alarm").setValue(0,7); + getField("Alarm").setValue(0,8); + getField("Alarm").setValue(0,9); + getField("Alarm").setValue(0,10); + getField("Alarm").setValue(0,11); + getField("Alarm").setValue(0,12); + getField("Alarm").setValue(0,13); + getField("Alarm").setValue(0,14); + getField("Alarm").setValue(0,15); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + SystemAlarms obj = new SystemAlarms(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public SystemAlarms GetInstance(UAVObjectManager objMngr, int instID) + { + return (SystemAlarms)(objMngr.getObject(SystemAlarms.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x89C3DCB2; + protected static final String NAME = "SystemAlarms"; + protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java new file mode 100644 index 000000000..d01b55b24 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java @@ -0,0 +1,157 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand + +generated from systemsettings.xml + **/ +public class SystemSettings extends UAVDataObject { + + public SystemSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AirframeTypeElemNames = new ArrayList(); + AirframeTypeElemNames.add("0"); + List AirframeTypeEnumOptions = new ArrayList(); + AirframeTypeEnumOptions.add("FixedWing"); + AirframeTypeEnumOptions.add("FixedWingElevon"); + AirframeTypeEnumOptions.add("FixedWingVtail"); + AirframeTypeEnumOptions.add("VTOL"); + AirframeTypeEnumOptions.add("HeliCP"); + AirframeTypeEnumOptions.add("QuadX"); + AirframeTypeEnumOptions.add("QuadP"); + AirframeTypeEnumOptions.add("Hexa"); + AirframeTypeEnumOptions.add("Octo"); + AirframeTypeEnumOptions.add("Custom"); + AirframeTypeEnumOptions.add("HexaX"); + AirframeTypeEnumOptions.add("OctoV"); + AirframeTypeEnumOptions.add("OctoCoaxP"); + AirframeTypeEnumOptions.add("OctoCoaxX"); + AirframeTypeEnumOptions.add("HexaCoax"); + AirframeTypeEnumOptions.add("Tri"); + fields.add( new UAVObjectField("AirframeType", "", UAVObjectField.FieldType.ENUM, AirframeTypeElemNames, AirframeTypeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("AirframeType").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + SystemSettings obj = new SystemSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public SystemSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (SystemSettings)(objMngr.getObject(SystemSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x3875CEE; + protected static final String NAME = "SystemSettings"; + protected static String DESCRIPTION = "Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java new file mode 100644 index 000000000..7c34360e9 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java @@ -0,0 +1,151 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * CPU and memory usage from OpenPilot computer. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +CPU and memory usage from OpenPilot computer. + +generated from systemstats.xml + **/ +public class SystemStats extends UAVDataObject { + + public SystemStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List FlightTimeElemNames = new ArrayList(); + FlightTimeElemNames.add("0"); + fields.add( new UAVObjectField("FlightTime", "ms", UAVObjectField.FieldType.UINT32, FlightTimeElemNames, null) ); + + List HeapRemainingElemNames = new ArrayList(); + HeapRemainingElemNames.add("0"); + fields.add( new UAVObjectField("HeapRemaining", "bytes", UAVObjectField.FieldType.UINT16, HeapRemainingElemNames, null) ); + + List CPULoadElemNames = new ArrayList(); + CPULoadElemNames.add("0"); + fields.add( new UAVObjectField("CPULoad", "%", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); + + List CPUTempElemNames = new ArrayList(); + CPUTempElemNames.add("0"); + fields.add( new UAVObjectField("CPUTemp", "C", UAVObjectField.FieldType.INT8, CPUTempElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + SystemStats obj = new SystemStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public SystemStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (SystemStats)(objMngr.getObject(SystemStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xAA26FFFA; + protected static final String NAME = "SystemStats"; + protected static String DESCRIPTION = "CPU and memory usage from OpenPilot computer. "; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java new file mode 100644 index 000000000..3ad065b5c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -0,0 +1,170 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Task information + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Task information + +generated from taskinfo.xml + **/ +public class TaskInfo extends UAVDataObject { + + public TaskInfo() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StackRemainingElemNames = new ArrayList(); + StackRemainingElemNames.add("System"); + StackRemainingElemNames.add("Actuator"); + StackRemainingElemNames.add("Attitude"); + StackRemainingElemNames.add("TelemetryTx"); + StackRemainingElemNames.add("TelemetryTxPri"); + StackRemainingElemNames.add("TelemetryRx"); + StackRemainingElemNames.add("GPS"); + StackRemainingElemNames.add("ManualControl"); + StackRemainingElemNames.add("Altitude"); + StackRemainingElemNames.add("AHRSComms"); + StackRemainingElemNames.add("Stabilization"); + StackRemainingElemNames.add("Guidance"); + StackRemainingElemNames.add("FlightPlan"); + fields.add( new UAVObjectField("StackRemaining", "bytes", UAVObjectField.FieldType.UINT16, StackRemainingElemNames, null) ); + + List RunningElemNames = new ArrayList(); + RunningElemNames.add("System"); + RunningElemNames.add("Actuator"); + RunningElemNames.add("Attitude"); + RunningElemNames.add("TelemetryTx"); + RunningElemNames.add("TelemetryTxPri"); + RunningElemNames.add("TelemetryRx"); + RunningElemNames.add("GPS"); + RunningElemNames.add("ManualControl"); + RunningElemNames.add("Altitude"); + RunningElemNames.add("AHRSComms"); + RunningElemNames.add("Stabilization"); + RunningElemNames.add("Guidance"); + RunningElemNames.add("FlightPlan"); + List RunningEnumOptions = new ArrayList(); + RunningEnumOptions.add("False"); + RunningEnumOptions.add("True"); + fields.add( new UAVObjectField("Running", "bool", UAVObjectField.FieldType.ENUM, RunningElemNames, RunningEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 10000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + TaskInfo obj = new TaskInfo(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public TaskInfo GetInstance(UAVObjectManager objMngr, int instID) + { + return (TaskInfo)(objMngr.getObject(TaskInfo.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x50F599F0; + protected static final String NAME = "TaskInfo"; + protected static String DESCRIPTION = "Task information"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java new file mode 100644 index 000000000..6995a02b0 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java @@ -0,0 +1,148 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Select baud rate of telemetry. Warning - this must match your modem. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Select baud rate of telemetry. Warning - this must match your modem. + +generated from telemetrysettings.xml + **/ +public class TelemetrySettings extends UAVDataObject { + + public TelemetrySettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SpeedElemNames = new ArrayList(); + SpeedElemNames.add("0"); + List SpeedEnumOptions = new ArrayList(); + SpeedEnumOptions.add("2400"); + SpeedEnumOptions.add("4800"); + SpeedEnumOptions.add("9600"); + SpeedEnumOptions.add("19200"); + SpeedEnumOptions.add("38400"); + SpeedEnumOptions.add("57600"); + SpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("Speed", "", UAVObjectField.FieldType.ENUM, SpeedElemNames, SpeedEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Speed").setValue(5); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + TelemetrySettings obj = new TelemetrySettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public TelemetrySettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (TelemetrySettings)(objMngr.getObject(TelemetrySettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA608C526; + protected static final String NAME = "TelemetrySettings"; + protected static String DESCRIPTION = "Select baud rate of telemetry. Warning - this must match your modem."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java new file mode 100644 index 000000000..4eca6ea82 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -0,0 +1,87 @@ +/** + ****************************************************************************** + * + * + * @file uavobjectsinittemplate.java + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief the template for the uavobjects init part + * $(GENERATEDWARNING) + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import org.openpilot.uavtalk.uavobjects.*; +import org.openpilot.uavtalk.UAVObjectManager; + +public class UAVObjectsInitialize { + + public static void register(UAVObjectManager objMngr) { + try { + objMngr.registerObject( new ActuatorCommand() ); + objMngr.registerObject( new ActuatorDesired() ); + objMngr.registerObject( new ActuatorSettings() ); + objMngr.registerObject( new AHRSCalibration() ); + objMngr.registerObject( new AHRSSettings() ); + objMngr.registerObject( new AhrsStatus() ); + objMngr.registerObject( new AttitudeActual() ); + objMngr.registerObject( new AttitudeRaw() ); + objMngr.registerObject( new AttitudeSettings() ); + objMngr.registerObject( new BaroAltitude() ); + objMngr.registerObject( new BatterySettings() ); + objMngr.registerObject( new FirmwareIAPObj() ); + objMngr.registerObject( new FlightBatteryState() ); + objMngr.registerObject( new FlightPlanControl() ); + objMngr.registerObject( new FlightPlanSettings() ); + objMngr.registerObject( new FlightPlanStatus() ); + objMngr.registerObject( new FlightTelemetryStats() ); + objMngr.registerObject( new GCSTelemetryStats() ); + objMngr.registerObject( new GPSPosition() ); + objMngr.registerObject( new GPSSatellites() ); + objMngr.registerObject( new GPSTime() ); + objMngr.registerObject( new GuidanceSettings() ); + objMngr.registerObject( new HomeLocation() ); + objMngr.registerObject( new I2CStats() ); + objMngr.registerObject( new ManualControlCommand() ); + objMngr.registerObject( new ManualControlSettings() ); + objMngr.registerObject( new MixerSettings() ); + objMngr.registerObject( new MixerStatus() ); + objMngr.registerObject( new NedAccel() ); + objMngr.registerObject( new ObjectPersistence() ); + objMngr.registerObject( new PositionActual() ); + objMngr.registerObject( new PositionDesired() ); + objMngr.registerObject( new RateDesired() ); + objMngr.registerObject( new SonarAltitude() ); + objMngr.registerObject( new StabilizationDesired() ); + objMngr.registerObject( new StabilizationSettings() ); + objMngr.registerObject( new SystemAlarms() ); + objMngr.registerObject( new SystemSettings() ); + objMngr.registerObject( new SystemStats() ); + objMngr.registerObject( new TaskInfo() ); + objMngr.registerObject( new TelemetrySettings() ); + objMngr.registerObject( new VelocityActual() ); + objMngr.registerObject( new VelocityDesired() ); + objMngr.registerObject( new WatchdogStatus() ); + + } catch (Exception e) { + e.printStackTrace(); + } + } +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java new file mode 100644 index 000000000..649e6c122 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control + +generated from velocityactual.xml + **/ +public class VelocityActual extends UAVDataObject { + + public VelocityActual() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm/s", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm/s", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm/s", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + VelocityActual obj = new VelocityActual(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public VelocityActual GetInstance(UAVObjectManager objMngr, int instID) + { + return (VelocityActual)(objMngr.getObject(VelocityActual.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x48009C88; + protected static final String NAME = "VelocityActual"; + protected static String DESCRIPTION = "Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java new file mode 100644 index 000000000..27f290898 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates). + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates). + +generated from velocitydesired.xml + **/ +public class VelocityDesired extends UAVDataObject { + + public VelocityDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "cm/s", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "cm/s", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "cm/s", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 1000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + VelocityDesired obj = new VelocityDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public VelocityDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (VelocityDesired)(objMngr.getObject(VelocityDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x122F5E3A; + protected static final String NAME = "VelocityDesired"; + protected static String DESCRIPTION = "Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates)."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java new file mode 100644 index 000000000..3adcad96b --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java @@ -0,0 +1,143 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * For monitoring the flags in the watchdog and especially the bootup flags + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +For monitoring the flags in the watchdog and especially the bootup flags + +generated from watchdogstatus.xml + **/ +public class WatchdogStatus extends UAVDataObject { + + public WatchdogStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List BootupFlagsElemNames = new ArrayList(); + BootupFlagsElemNames.add("0"); + fields.add( new UAVObjectField("BootupFlags", "", UAVObjectField.FieldType.UINT16, BootupFlagsElemNames, null) ); + + List ActiveFlagsElemNames = new ArrayList(); + ActiveFlagsElemNames.add("0"); + fields.add( new UAVObjectField("ActiveFlags", "", UAVObjectField.FieldType.UINT16, ActiveFlagsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 5000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.loggingUpdatePeriod = 5000; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + WatchdogStatus obj = new WatchdogStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public WatchdogStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (WatchdogStatus)(objMngr.getObject(WatchdogStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD646E910; + protected static final String NAME = "WatchdogStatus"; + protected static String DESCRIPTION = "For monitoring the flags in the watchdog and especially the bootup flags"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file From f33862509216ebd4383db53b0f3b42b9ac0fc851 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:12:32 -0600 Subject: [PATCH 206/543] Removed various debugging outputs and exceptions for now (will add back in a more principled manner later). Also updated the auto generated code. --- androidgcs/.classpath | 1 + .../org/openpilot/uavtalk/UAVDataObject.java | 2 +- .../src/org/openpilot/uavtalk/UAVObject.java | 5 +- .../org/openpilot/uavtalk/UAVObjectField.java | 30 +++++++---- .../templates/uavobjectsinittemplate.java | 52 ++++--------------- .../templates/uavobjecttemplate.java | 6 +-- .../java/uavobjectgeneratorjava.cpp | 4 +- 7 files changed, 37 insertions(+), 63 deletions(-) diff --git a/androidgcs/.classpath b/androidgcs/.classpath index b24a2abf5..6f3f456df 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -1,6 +1,7 @@ + diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index f0a2248f5..de04f81c5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -9,7 +9,7 @@ public abstract class UAVDataObject extends UAVObject { * @param isSet * @param name */ - public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) throws Exception { + public UAVDataObject(int objID, Boolean isSingleInst, Boolean isSet, String name) { super(objID, isSingleInst, name); mobj = null; this.isSet = isSet; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index bf2c87d7e..cc6718ebd 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -105,10 +105,9 @@ public abstract class UAVObject { * When unable to unpack a field */ public void initializeFields(List fields, ByteBuffer data, - int numBytes) throws Exception { + int numBytes) { // TODO: QMutexLocker locker(mutex); this.numBytes = numBytes; -// this.data = data; this.fields = fields; // Initialize fields for (int n = 0; n < fields.size(); ++n) { @@ -288,7 +287,7 @@ public abstract class UAVObject { * @throws Exception * @returns The number of bytes copied */ - public int unpack(ByteBuffer dataIn) throws Exception { + public int unpack(ByteBuffer dataIn) { if( dataIn == null ) return 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 78ebd7b52..a5fc6b7da 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -90,8 +90,8 @@ public class UAVObjectField { * to the arm/uavtalk standard (little endian) * @param dataOut * @return the number of bytes added - * @throws Exception */ - public int pack(ByteBuffer dataOut) throws Exception { + **/ + public int pack(ByteBuffer dataOut) { //QMutexLocker locker(obj->getMutex()); // Pack each element in output buffer dataOut.order(ByteOrder.LITTLE_ENDIAN); @@ -147,7 +147,7 @@ public class UAVObjectField { break; case STRING: // TODO: Implement strings - throw new Exception("Strings not yet implemented"); + throw new Error("Strings not yet implemented"); } // Done return getNumBytes(); @@ -358,13 +358,13 @@ public class UAVObjectField { } } - public double getDouble() throws Exception { return getDouble(0); }; - public double getDouble(int index) throws Exception { + public double getDouble() { return getDouble(0); }; + public double getDouble(int index) { return Double.valueOf((Double) getValue(index)); } - public void setDouble(double value) throws Exception { setDouble(value, 0); }; - public void setDouble(double value, int index) throws Exception { + public void setDouble(double value) { setDouble(value, 0); }; + public void setDouble(double value, int index) { setValue(value, index); } @@ -436,9 +436,7 @@ public class UAVObjectField { String sout = new String(); sout += name + ": [ "; for (int n = 0; n < numElements; ++n) - { sout += String.valueOf(n) + "(" + getValue(n) + ") "; - } sout += "] " + units + "\n"; return sout; @@ -488,6 +486,18 @@ public class UAVObjectField { ((ArrayList) data).add((long) 0); } break; + case FLOAT32: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((float) 0); + } + break; + case ENUM: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((byte) 0); + } + break; } } @@ -546,8 +556,6 @@ public class UAVObjectField { numBytesPerElement = 0; } clear(); - - System.out.println(this); } /** diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjectsinittemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjectsinittemplate.java index 5185ab237..7f9edb791 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjectsinittemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjectsinittemplate.java @@ -26,50 +26,18 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -package org.openpilot.uavtalk; +package org.openpilot.uavtalk.uavobjects; import org.openpilot.uavtalk.uavobjects.*; -import org.openpilot.uavtalk.UAVObject; -import java.util.HashMap; +import org.openpilot.uavtalk.UAVObjectManager; -public class UAVObjects { - - private static UAVObject[] uavobjects=null; - private static HashMap id2obj; - - public static void init() { - if (uavobjects==null) { - uavobjects=new UAVObject[] { -$(OBJINIT) - }; - id2obj=new HashMap(); - for (int i=0;i< uavobjects.length;i++) - id2obj.put(uavobjects[i].getObjID(),i); +public class UAVObjectsInitialize { + + public static void register(UAVObjectManager objMngr) { + try { +$(OBJINIT) + } catch (Exception e) { + e.printStackTrace(); + } } - } - - public static UAVObject[] getUAVObjectArray() { - return uavobjects; - } - - public static boolean hasObjectWithID(int id) { - return id2obj.containsKey(id); - } - - public static UAVObject getObjectByID(int id) { - if (!hasObjectWithID(id)) - return null; - return uavobjects[(Integer)id2obj.get(id)]; - } - - public static UAVObject getObjectByName(String name) { - return uavobjects[0]; - } - - public static void printAll() { - for (UAVObject obj : uavobjects) - System.out.println(obj.getObjName()); - } - -$(OBJGETTER) } \ No newline at end of file diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index af8f48fce..64e2461f5 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -36,7 +36,6 @@ import java.util.ListIterator; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVObject; import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVMetaObject; import org.openpilot.uavtalk.UAVObjectField; /** @@ -46,7 +45,7 @@ generated from $(XMLFILE) **/ public class $(NAME) extends UAVDataObject { - public $(NAME)() throws Exception { + public $(NAME)() { super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); List fields = new ArrayList(); @@ -57,10 +56,9 @@ $(FIELDSINIT) int numBytes = 0; ListIterator li = fields.listIterator(); while(li.hasNext()) { - numBytes += li.next().getNumBytesElement(); + numBytes += li.next().getNumBytes(); } NUMBYTES = numBytes; - // Initialize object initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index 7319b7767..b8d4b33d5 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -54,14 +54,14 @@ bool UAVObjectGeneratorJava::generate(UAVObjectParser* parser,QString templatepa ObjectInfo* info=parser->getObjectByIndex(objidx); process_object(info); - javaObjInit.append(" objMngr->registerObject( new " + info->name + "() );\n"); + javaObjInit.append("\t\t\tobjMngr.registerObject( new " + info->name + "() );\n"); objInc.append("#include \"" + info->namelc + ".h\"\n"); } // Write the gcs object inialization files javaInitTemplate.replace( QString("$(OBJINC)"), objInc); javaInitTemplate.replace( QString("$(OBJINIT)"), javaObjInit); - bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/uavobjectsinit.java", javaInitTemplate ); + bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/UAVObjectsInitialize.java", javaInitTemplate ); if (!res) { cout << "Error: Could not write output files" << endl; return false; From 6dd509ded3547b146d52c12066f28b31525c139b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:33:56 -0600 Subject: [PATCH 207/543] Make the initial values for enums be the string. Make setValue accept numerical or string constants for enums. Only returns a string though. --- .../src/org/openpilot/uavtalk/UAVObjectField.java | 10 ++++++++-- .../generators/java/uavobjectgeneratorjava.cpp | 8 ++++---- 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index a5fc6b7da..bb525a5e0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -343,8 +343,14 @@ public class UAVObjectField { break; } case ENUM: - { - byte val = (byte) options.indexOf((String) data); + { + byte val; + try { + // Test if numeric constant passed in + val = ((Number) data).byteValue(); + } catch (Exception e) { + val = (byte) options.indexOf((String) data); + } //if(val < 0) throw new Exception("Enumerated value not found"); List l = (List) this.data; l.set(index, val); diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index b8d4b33d5..e942b238f 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -210,9 +210,9 @@ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) { if ( info->fields[n]->type == FIELDTYPE_ENUM ) { - initfields.append( QString("\t\tgetField(\"%1\").setValue(%2);\n") + initfields.append( QString("\t\tgetField(\"%1\").setValue(\"%2\");\n") .arg( info->fields[n]->name ) - .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[0] ) ) ); + .arg( info->fields[n]->defaultValues[0] ) ); } else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) { @@ -233,10 +233,10 @@ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) for (int idx = 0; idx < info->fields[n]->numElements; ++idx) { if ( info->fields[n]->type == FIELDTYPE_ENUM ) { - initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") + initfields.append( QString("\t\tgetField(\"%1\").setValue(\"%3\",%2);\n") .arg( info->fields[n]->name ) .arg( idx ) - .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[idx] ) ) ); + .arg( info->fields[n]->defaultValues[idx] ) ); } else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) { initfields.append( QString("\t\tgetField(\"%1\").setValue(%3,%2);\n") From 1f202089d197dc54571d1b1d3b341c5c4859591f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 13:36:49 -0600 Subject: [PATCH 208/543] Some cosmetic changes, also initialize the Metadata properly --- .../src/org/openpilot/uavtalk/UAVMetaObject.java | 13 ++++++++++++- androidgcs/src/org/openpilot/uavtalk/UAVObject.java | 2 +- .../src/org/openpilot/uavtalk/UAVObjectField.java | 6 +----- 3 files changed, 14 insertions(+), 7 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index 70e661d46..98e4bd626 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -3,12 +3,15 @@ package org.openpilot.uavtalk; import java.nio.ByteBuffer; import java.util.ArrayList; import java.util.List; +import java.util.ListIterator; public class UAVMetaObject extends UAVObject { public UAVMetaObject(int objID, String name, UAVDataObject parent) throws Exception { super(objID, true, name); this.parent = parent; + + ownMetadata = new Metadata(); ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; @@ -48,9 +51,17 @@ public class UAVMetaObject extends UAVObject { fields.add( new UAVObjectField("Logging Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); fields.add( new UAVObjectField("Logging Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + + // Initialize object + // Initialize parent super.initialize(0); - super.initializeFields(fields, ByteBuffer.allocate(10), 10); + initializeFields(fields, ByteBuffer.allocate(numBytes), numBytes); // Setup metadata of parent parentMetadata = parent.getDefaultMetadata(); diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index cc6718ebd..a990def2c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -461,7 +461,7 @@ public abstract class UAVObject { * Return a string with the object information (only the header) */ public String toStringBrief() { - return getName() + " ( " + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; + return getName() + " (" + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index bb525a5e0..0b72c33c8 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -440,11 +440,7 @@ public class UAVObjectField { public String toString() { String sout = new String(); - sout += name + ": [ "; - for (int n = 0; n < numElements; ++n) - sout += String.valueOf(n) + "(" + getValue(n) + ") "; - - sout += "] " + units + "\n"; + sout += name + ": " + ((List) data).toString() + " (" + units + ")\n"; return sout; } From 689afeabb5bbfbe466f0f096762adc8d673500c7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 18:22:11 -0600 Subject: [PATCH 209/543] Initial implementation of UAVTalk protocol and a test platform for it and the UAVObjectManager --- .../openpilot/uavtalk/UAVObjectManager.java | 22 + .../src/org/openpilot/uavtalk/UAVTalk.java | 808 ++++++++++++++++++ .../org/openpilot/uavtalk/ObjMngrTest.java | 22 + .../tests/org/openpilot/uavtalk/TalkTest.java | 74 ++ 4 files changed, 926 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/UAVTalk.java create mode 100644 androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java create mode 100644 androidgcs/tests/org/openpilot/uavtalk/TalkTest.java diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index d75b14b85..2e531fc85 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -118,6 +118,7 @@ public class UAVObjectManager { // Create metaobject String mname = obj.getName(); mname += "Meta"; + UAVMetaObject mobj = new UAVMetaObject(obj.getObjID()+1, mname, obj); // Initialize object obj.initialize(0, mobj); @@ -224,6 +225,17 @@ public class UAVObjectManager { */ } + + /** + * Returns a specific object by name only, returns instance ID zero + * @param name The object name + * @return The object or null if not found + */ + public UAVObject getObject(String name) + { + return getObject(name, 0, 0); + } + /** * Get a specific object given its name and instance ID * @returns The object is found or NULL if not @@ -233,6 +245,16 @@ public class UAVObjectManager { return getObject(name, 0, instId); } + /** + * Get a specific object with given object ID and instance ID zero + * @param objId the object id + * @returns The object is found or NULL if not + */ + public UAVObject getObject(int objId) + { + return getObject(null, objId, 0); + } + /** * Get a specific object given its object and instance ID * @returns The object is found or NULL if not diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java new file mode 100644 index 000000000..07b061bc9 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -0,0 +1,808 @@ +package org.openpilot.uavtalk; + +import java.io.ByteArrayInputStream; +import java.io.ByteArrayOutputStream; +import java.io.IOException; +import java.io.InputStream; +import java.io.OutputStream; +import java.nio.ByteBuffer; +import java.nio.ByteOrder; + +public class UAVTalk { + + /** + * Constants + */ + private static final int SYNC_VAL = 0x3C; + + private static final short crc_table[] = { + 0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d, + 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, + 0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd, + 0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, 0xb4, 0xb3, 0xba, 0xbd, + 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, + 0xb7, 0xb0, 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a, + 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a, + 0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, + 0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4, + 0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, 0xd4, + 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, + 0x19, 0x1e, 0x17, 0x10, 0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34, + 0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f, 0x6a, 0x6d, 0x64, 0x63, + 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, + 0xae, 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83, + 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3 + }; + + enum RxStateType {STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS}; + + static final int TYPE_MASK = 0xFC; + static final int TYPE_VER = 0x20; + static final int TYPE_OBJ = (TYPE_VER | 0x00); + static final int TYPE_OBJ_REQ = (TYPE_VER | 0x01); + static final int TYPE_OBJ_ACK = (TYPE_VER | 0x02); + static final int TYPE_ACK = (TYPE_VER | 0x03); + + static final int MIN_HEADER_LENGTH = 8; // sync(1), type (1), size(2), object ID(4) + static final int MAX_HEADER_LENGTH = 10; // sync(1), type (1), size(2), object ID (4), instance ID(2, not used in single objects) + + static final int CHECKSUM_LENGTH = 1; + + static final int MAX_PAYLOAD_LENGTH = 256; + + static final int MAX_PACKET_LENGTH = (MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH); + + static final int ALL_INSTANCES = 0xFFFF; + static final int TX_BUFFER_SIZE = 2*1024; + + /** + * Private data + */ + InputStream inStream; + OutputStream outStream; + UAVObjectManager objMngr; + + UAVObject respObj; + boolean respAllInstances; + // Variables used by the receive state machine + ByteBuffer rxTmpBuffer /* 4 */; + ByteBuffer rxBuffer; + int rxType; + int rxObjId; + int rxInstId; + int rxLength; + int rxPacketLength; + + int rxCSPacket, rxCS; + int rxCount; + int packetSize; + RxStateType rxState; + ComStats stats = new ComStats(); + + /** + * Comm stats + */ + public class ComStats { + public int txBytes = 0; + public int rxBytes = 0; + public int txObjectBytes = 0; + public int rxObjectBytes = 0; + public int rxObjects = 0; + public int txObjects = 0; + public int txErrors = 0; + public int rxErrors = 0; + } + + /** + * Constructor + */ + public UAVTalk(InputStream inStream, OutputStream outStream, UAVObjectManager objMngr) + { + this.objMngr = objMngr; + this.inStream = inStream; + this.outStream = outStream; + + rxState = RxStateType.STATE_SYNC; + rxPacketLength = 0; + + //mutex = new QMutex(QMutex::Recursive); + + respObj = null; + resetStats(); + rxTmpBuffer = ByteBuffer.allocate(4); + rxTmpBuffer.order(ByteOrder.LITTLE_ENDIAN); + rxBuffer = ByteBuffer.allocate(MAX_PAYLOAD_LENGTH); + rxBuffer.order(ByteOrder.LITTLE_ENDIAN); + + // TOOD: Callback connect(io, SIGNAL(readyRead()), this, SLOT(processInputStream())); + } + + /** + * Reset the statistics counters + */ + public void resetStats() + { + //QMutexLocker locker(mutex); + stats = new ComStats(); + } + + /** + * Get the statistics counters + */ + public ComStats getStats() + { + //QMutexLocker locker(mutex); + return stats; + } + + /** + * Called each time there are data in the input buffer + */ + public void processInputStream() + { + int val; + + while (true) + { + try { + //inStream.wait(); + val = inStream.read(); + } /*catch (InterruptedException e) { + // TODO Auto-generated catch block + System.out.println("Connection was aborted\n"); + e.printStackTrace(); + break; + }*/ catch (IOException e) { + // TODO Auto-generated catch block + System.out.println("Error reading from stream\n"); + e.printStackTrace(); + break; + } + //System.out.println("Received byte " + val + " in state + " + rxState); + processInputByte(val); + } + } + + /** + * Request an update for the specified object, on success the object data would have been + * updated by the GCS. + * \param[in] obj Object to update + * \param[in] allInstances If set true then all instances will be updated + * \return Success (true), Failure (false) + */ + public boolean sendObjectRequest(UAVObject obj, boolean allInstances) + { + //QMutexLocker locker(mutex); + return objectTransaction(obj, TYPE_OBJ_REQ, allInstances); + } + + /** + * Send the specified object through the telemetry link. + * \param[in] obj Object to send + * \param[in] acked Selects if an ack is required + * \param[in] allInstances If set true then all instances will be updated + * \return Success (true), Failure (false) + */ + public boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) + { + //QMutexLocker locker(mutex); + if (acked) + { + return objectTransaction(obj, TYPE_OBJ_ACK, allInstances); + } + else + { + return objectTransaction(obj, TYPE_OBJ, allInstances); + } + } + + /** + * Cancel a pending transaction + */ + public void cancelTransaction() + { + //QMutexLocker locker(mutex); + respObj = null; + } + + /** + * Execute the requested transaction on an object. + * \param[in] obj Object + * \param[in] type Transaction type + * TYPE_OBJ: send object, + * TYPE_OBJ_REQ: request object update + * TYPE_OBJ_ACK: send object with an ack + * \param[in] allInstances If set true then all instances will be updated + * \return Success (true), Failure (false) + */ + public boolean objectTransaction(UAVObject obj, int type, boolean allInstances) + { + // Send object depending on if a response is needed + if (type == TYPE_OBJ_ACK || type == TYPE_OBJ_REQ) + { + if ( transmitObject(obj, type, allInstances) ) + { + respObj = obj; + respAllInstances = allInstances; + return true; + } + else + { + return false; + } + } + else if (type == TYPE_OBJ) + { + return transmitObject(obj, TYPE_OBJ, allInstances); + } + else + { + return false; + } + } + + /** + * Process an byte from the telemetry stream. + * \param[in] rxbyte Received byte + * \return Success (true), Failure (false) + */ + public boolean processInputByte(int rxbyte) + { + assert(objMngr != null); + + // Update stats + stats.rxBytes++; + + rxPacketLength++; // update packet byte count + + // Receive state machine + switch (rxState) + { + case STATE_SYNC: + + if (rxbyte != SYNC_VAL) + break; + + // Initialize and update CRC + rxCS = updateCRC(0, rxbyte); + + rxPacketLength = 1; + + rxState = RxStateType.STATE_TYPE; + break; + + case STATE_TYPE: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + if ((rxbyte & TYPE_MASK) != TYPE_VER) + { + rxState = RxStateType.STATE_SYNC; + break; + } + + rxType = rxbyte; + + packetSize = 0; + + rxState = RxStateType.STATE_SIZE; + rxCount = 0; + break; + + case STATE_SIZE: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + if (rxCount == 0) + { + packetSize += rxbyte; + rxCount++; + break; + } + + packetSize += (rxbyte << 8) & 0xff00; + + if (packetSize < MIN_HEADER_LENGTH || packetSize > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH) + { // incorrect packet size + rxState = RxStateType.STATE_SYNC; + break; + } + + rxCount = 0; + rxState = RxStateType.STATE_OBJID; + rxTmpBuffer.position(0); + break; + + case STATE_OBJID: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + rxTmpBuffer.put(rxCount++, (byte) (rxbyte & 0xff)); + if (rxCount < 4) + break; + + // Search for object, if not found reset state machine + rxObjId = rxTmpBuffer.getInt(0); + { + UAVObject rxObj = objMngr.getObject(rxObjId); + if (rxObj == null) + { + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + // Determine data length + if (rxType == TYPE_OBJ_REQ || rxType == TYPE_ACK) + rxLength = 0; + else + rxLength = rxObj.getNumBytes(); + + // Check length and determine next state + if (rxLength >= MAX_PAYLOAD_LENGTH) + { + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + // Check the lengths match + if ((rxPacketLength + rxLength) != packetSize) + { // packet error - mismatched packet size + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + // Check if this is a single instance object (i.e. if the instance ID field is coming next) + if (rxObj.isSingleInstance()) + { + // If there is a payload get it, otherwise receive checksum + if (rxLength > 0) + rxState = RxStateType.STATE_DATA; + else + rxState = RxStateType.STATE_CS; + rxInstId = 0; + rxCount = 0; + } + else + { + rxState = RxStateType.STATE_INSTID; + rxCount = 0; + } + } + + break; + + case STATE_INSTID: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + rxTmpBuffer.put(rxCount++, (byte) (rxbyte & 0xff)); + if (rxCount < 2) + break; + + rxInstId = rxTmpBuffer.getShort(0); + + rxCount = 0; + + // If there is a payload get it, otherwise receive checksum + if (rxLength > 0) + rxState = RxStateType.STATE_DATA; + else + rxState = RxStateType.STATE_CS; + + break; + + case STATE_DATA: + + // Update CRC + rxCS = updateCRC(rxCS, rxbyte); + + //System.out.println(rxCount + "/" + rxLength); + rxBuffer.put(rxCount++, (byte) (rxbyte & 0xff)); + if (rxCount < rxLength) + break; + + rxState = RxStateType.STATE_CS; + rxCount = 0; + break; + + case STATE_CS: + + // The CRC byte + rxCSPacket = rxbyte; + + if (rxCS != rxCSPacket) + { // packet error - faulty CRC + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + if (rxPacketLength != (packetSize + 1)) + { // packet error - mismatched packet size + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } + + //mutex->lock(); + rxBuffer.position(0); + receiveObject(rxType, rxObjId, rxInstId, rxBuffer); + stats.rxObjectBytes += rxLength; + stats.rxObjects++; + //mutex->unlock(); + + rxState = RxStateType.STATE_SYNC; + break; + + default: + rxState = RxStateType.STATE_SYNC; + stats.rxErrors++; + } + + // Done + return true; + } + + /** + * Receive an object. This function process objects received through the telemetry stream. + * \param[in] type Type of received message (TYPE_OBJ, TYPE_OBJ_REQ, TYPE_OBJ_ACK, TYPE_ACK) + * \param[in] obj Handle of the received object + * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. + * \param[in] data Data buffer + * \param[in] length Buffer length + * \return Success (true), Failure (false) + */ + public boolean receiveObject(int type, int objId, int instId, ByteBuffer data) + { + assert(objMngr != null); + + UAVObject obj = null; + boolean error = false; + boolean allInstances = (instId == ALL_INSTANCES? true : false); + + System.out.println("Received object: " + objId + " " + objMngr.getObject(objId).getName()); + // Process message type + switch (type) { + case TYPE_OBJ: + // All instances, not allowed for OBJ messages + if (!allInstances) + { + // Get object and update its data + obj = updateObject(objId, instId, data); + // Check if an ack is pending + if ( obj != null ) + { + updateAck(obj); + } + else + { + error = true; + } + } + else + { + error = true; + } + break; + case TYPE_OBJ_ACK: + // All instances, not allowed for OBJ_ACK messages + if (!allInstances) + { + // Get object and update its data + obj = updateObject(objId, instId, data); + // Transmit ACK + if ( obj != null ) + { + transmitObject(obj, TYPE_ACK, false); + } + else + { + error = true; + } + } + else + { + error = true; + } + break; + case TYPE_OBJ_REQ: + // Get object, if all instances are requested get instance 0 of the object + if (allInstances) + { + obj = objMngr.getObject(objId); + } + else + { + obj = objMngr.getObject(objId, instId); + } + // If object was found transmit it + if (obj != null) + { + transmitObject(obj, TYPE_OBJ, allInstances); + } + else + { + error = true; + } + break; + case TYPE_ACK: + // All instances, not allowed for ACK messages + if (!allInstances) + { + // Get object + obj = objMngr.getObject(objId, instId); + // Check if an ack is pending + if (obj != null) + { + updateAck(obj); + } + else + { + error = true; + } + } + break; + default: + error = true; + } + // Done + return !error; + } + + /** + * Update the data of an object from a byte array (unpack). + * If the object instance could not be found in the list, then a + * new one is created. + */ + public UAVObject updateObject(int objId, int instId, ByteBuffer data) + { + assert(objMngr != null); + + // Get object + UAVObject obj = objMngr.getObject(objId, instId); + // If the instance does not exist create it + if (obj == null) + { + // Get the object type + UAVObject tobj = objMngr.getObject(objId); + if (tobj == null) + { + return null; + } + // Make sure this is a data object + UAVDataObject dobj = null; + try { + dobj = (UAVDataObject) tobj; + } catch (Exception e) { + // Failed to cast to a data object + return null; + } + + // Create a new instance, unpack and register + UAVDataObject instobj = dobj.clone(instId); + try { + if ( !objMngr.registerObject(instobj) ) + { + return null; + } + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + instobj.unpack(data); + return instobj; + } + else + { + // Unpack data into object instance + // System.out.println("Unpacking: " + data.position() + " / " + data.capacity() ); + obj.unpack(data); + return obj; + } + } + + /** + * Check if a transaction is pending and if yes complete it. + */ + public void updateAck(UAVObject obj) + { + if (respObj != null && respObj.getObjID() == obj.getObjID() && (respObj.getInstID() == obj.getInstID() || respAllInstances)) + { + respObj = null; + // TODO: Signals +// emit transactionCompleted(obj); + } + } + + /** + * Send an object through the telemetry link. + * \param[in] obj Object to send + * \param[in] type Transaction type + * \param[in] allInstances True is all instances of the object are to be sent + * \return Success (true), Failure (false) + */ + public boolean transmitObject(UAVObject obj, int type, boolean allInstances) + { + // If all instances are requested on a single instance object it is an error + if (allInstances && obj.isSingleInstance()) + { + allInstances = false; + } + + // Process message type + if ( type == TYPE_OBJ || type == TYPE_OBJ_ACK ) + { + if (allInstances) + { + // Get number of instances + int numInst = objMngr.getNumInstances(obj.getObjID()); + // Send all instances + for (int instId = 0; instId < numInst; ++instId) + { + UAVObject inst = objMngr.getObject(obj.getObjID(), instId); + transmitSingleObject(inst, type, false); + } + return true; + } + else + { + return transmitSingleObject(obj, type, false); + } + } + else if (type == TYPE_OBJ_REQ) + { + return transmitSingleObject(obj, TYPE_OBJ_REQ, allInstances); + } + else if (type == TYPE_ACK) + { + if (!allInstances) + { + return transmitSingleObject(obj, TYPE_ACK, false); + } + else + { + return false; + } + } + else + { + return false; + } + } + + + /** + * Send an object through the telemetry link. + * \param[in] obj Object handle to send + * \param[in] type Transaction type + * \return Success (true), Failure (false) + */ + public boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) + { + int length; + int dataOffset; + int objId; + int instId; + int allInstId = ALL_INSTANCES; + + assert(objMngr != null && outStream != null); + + ByteBuffer bbuf = ByteBuffer.allocate(MAX_PACKET_LENGTH); + bbuf.order(ByteOrder.LITTLE_ENDIAN); + + // Determine data length + if (type == TYPE_OBJ_REQ || type == TYPE_ACK) + { + length = 0; + } + else + { + length = obj.getNumBytes(); + } + + // Setup type and object id fields + bbuf.put((byte) (SYNC_VAL & 0xff)); + bbuf.put((byte) (type & 0xff)); + bbuf.putShort((short) (length + + 2 /* SYNC, Type */ + + 2 /* Size */ + + 4 /* ObjID */ + + (obj.isSingleInstance() ? 0 : 2) )); + bbuf.putInt(obj.getObjID()); + + // Setup instance ID if one is required + if ( !obj.isSingleInstance() ) + { + // Check if all instances are requested + if (allInstances) + bbuf.putShort((short) (allInstId & 0xffff)); + else + bbuf.putShort((short) (obj.getInstID() & 0xffff)); + } + + // Check length + if (length >= MAX_PAYLOAD_LENGTH) + return false; + + // Copy data (if any) + if (length > 0) + try { + if ( obj.pack(bbuf) == 0) + return false; + } catch (Exception e) { + // TODO Auto-generated catch block + e.printStackTrace(); + return false; + } + + // Calculate checksum + bbuf.put((byte) (updateCRC(0, bbuf.array()) & 0xff)); + + try { + outStream.write(bbuf.array()); + } catch (IOException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + return false; + } + +// //TODO: Need to use a different outStream type and check that the backlog isn't more than TX_BUFFER_SIZE +// // Send buffer, check that the transmit backlog does not grow above limit +// if ( io->bytesToWrite() < TX_BUFFER_SIZE ) +// { +// io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH); +// } +// else +// { +// ++stats.txErrors; +// return false; +// } + + // Update stats + ++stats.txObjects; + stats.txBytes += bbuf.position(); + stats.txObjectBytes += length; + + // Done + return true; + } + + /** + * Update the crc value with new data. + * + * Generated by pycrc v0.7.5, http://www.tty1.net/pycrc/ + * using the configuration: + * Width = 8 + * Poly = 0x07 + * XorIn = 0x00 + * ReflectIn = False + * XorOut = 0x00 + * ReflectOut = False + * Algorithm = table-driven + * + * \param crc The current crc value. + * \param data Pointer to a buffer of \a data_len bytes. + * \param length Number of bytes in the \a data buffer. + * \return The updated crc value. + */ + int updateCRC(int crc, int data) + { + return crc_table[crc ^ (data & 0xff)]; + } + int updateCRC(int crc, byte [] data) + { + for (int i = 0; i < data.length; i++) + crc = updateCRC(crc, (int) data[i]); + return crc; + } + + + +} diff --git a/androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java b/androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java new file mode 100644 index 000000000..0131d1246 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java @@ -0,0 +1,22 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import org.junit.BeforeClass; +import org.junit.Test; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; + +public class ObjMngrTest { + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + } + + @Test + public void testGetObjects() { + UAVObjectManager objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); +// System.out.println(objMngr.getObject("ActuatorSettings", 0)); + } + +} diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java new file mode 100644 index 000000000..6dc23530e --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java @@ -0,0 +1,74 @@ +package org.openpilot.uavtalk; +import static org.junit.Assert.*; + +import java.io.IOException; +import java.io.InputStream; +import java.io.InputStreamReader; +import java.io.OutputStream; +import java.net.DatagramSocket; +import java.net.InetAddress; +import java.net.Socket; +import java.nio.ByteBuffer; + +import org.junit.BeforeClass; +import org.junit.Test; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; +import org.openpilot.uavtalk.UAVTalk; + + +public class TalkTest { + + static UAVObjectManager objMngr; + static final String IP_ADDRDESS = new String("127.0.0.1"); + static final int PORT_NUM = 8000; + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + } + + @Test + public void testProcessInputStream() { + Socket connection = null; + UAVTalk talk = null; + try{ + InetAddress ip = InetAddress.getByName(IP_ADDRDESS); + connection = new Socket(ip, PORT_NUM); + } catch (Exception e) { + e.printStackTrace(); + fail("Couldn't connect to test platform"); + } + + try { + talk = new UAVTalk(connection.getInputStream(), connection.getOutputStream(), objMngr); + } catch (IOException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + fail("Couldn't construct UAVTalk object"); + } + + talk.processInputStream(); + } + + @Test + public void testSendObjectRequest() { + fail("Not yet implemented"); + } + + @Test + public void testSendObject() { + fail("Not yet implemented"); + } + + @Test + public void testReceiveObject() { + fail("Not yet implemented"); + } + + @Test + public void testUpdateObject() { + fail("Not yet implemented"); + } + +} From c7961b9f384c9f8e98cfe99399e49a4ffc4b3dea Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 6 Mar 2011 18:22:39 -0600 Subject: [PATCH 210/543] Updates to various objects --- .../uavtalk/uavobjects/AHRSCalibration.java | 2 +- .../uavtalk/uavobjects/AHRSSettings.java | 4 +- .../uavtalk/uavobjects/ActuatorSettings.java | 44 +++++++++---------- .../uavtalk/uavobjects/BatterySettings.java | 2 +- .../uavtalk/uavobjects/FlightPlanControl.java | 2 +- .../uavtalk/uavobjects/FlightPlanStatus.java | 4 +- .../uavtalk/uavobjects/GuidanceSettings.java | 4 +- .../uavtalk/uavobjects/HomeLocation.java | 2 +- .../uavobjects/ManualControlSettings.java | 44 +++++++++---------- .../uavtalk/uavobjects/MixerSettings.java | 16 +++---- .../uavtalk/uavobjects/SystemAlarms.java | 32 +++++++------- .../uavtalk/uavobjects/SystemSettings.java | 2 +- .../uavtalk/uavobjects/TelemetrySettings.java | 2 +- 13 files changed, 80 insertions(+), 80 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java index a3096ad39..922582398 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java @@ -171,7 +171,7 @@ public class AHRSCalibration extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("measure_var").setValue(0); + getField("measure_var").setValue("SET"); getField("accel_bias").setValue(-73.5,0); getField("accel_bias").setValue(-73.5,1); getField("accel_bias").setValue(73.5,2); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java index a38915c28..c49c04778 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java @@ -132,10 +132,10 @@ public class AHRSSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Algorithm").setValue(1); + getField("Algorithm").setValue("INSGPS_INDOOR_NOMAG"); getField("Downsampling").setValue(20); getField("UpdatePeriod").setValue(1); - getField("BiasCorrectedRaw").setValue(0); + getField("BiasCorrectedRaw").setValue("TRUE"); getField("YawBias").setValue(0); getField("PitchBias").setValue(0); getField("RollBias").setValue(0); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java index ebbfaeb17..542b433d1 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java @@ -358,20 +358,20 @@ public class ActuatorSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("FixedWingRoll1").setValue(8); - getField("FixedWingRoll2").setValue(8); - getField("FixedWingPitch1").setValue(8); - getField("FixedWingPitch2").setValue(8); - getField("FixedWingYaw").setValue(8); - getField("FixedWingThrottle").setValue(8); - getField("VTOLMotorN").setValue(8); - getField("VTOLMotorNE").setValue(8); - getField("VTOLMotorE").setValue(8); - getField("VTOLMotorSE").setValue(8); - getField("VTOLMotorS").setValue(8); - getField("VTOLMotorSW").setValue(8); - getField("VTOLMotorW").setValue(8); - getField("VTOLMotorNW").setValue(8); + getField("FixedWingRoll1").setValue("None"); + getField("FixedWingRoll2").setValue("None"); + getField("FixedWingPitch1").setValue("None"); + getField("FixedWingPitch2").setValue("None"); + getField("FixedWingYaw").setValue("None"); + getField("FixedWingThrottle").setValue("None"); + getField("VTOLMotorN").setValue("None"); + getField("VTOLMotorNE").setValue("None"); + getField("VTOLMotorE").setValue("None"); + getField("VTOLMotorSE").setValue("None"); + getField("VTOLMotorS").setValue("None"); + getField("VTOLMotorSW").setValue("None"); + getField("VTOLMotorW").setValue("None"); + getField("VTOLMotorNW").setValue("None"); getField("ChannelUpdateFreq").setValue(50,0); getField("ChannelUpdateFreq").setValue(50,1); getField("ChannelUpdateFreq").setValue(50,2); @@ -400,14 +400,14 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelMin").setValue(1000,5); getField("ChannelMin").setValue(1000,6); getField("ChannelMin").setValue(1000,7); - getField("ChannelType").setValue(0,0); - getField("ChannelType").setValue(0,1); - getField("ChannelType").setValue(0,2); - getField("ChannelType").setValue(0,3); - getField("ChannelType").setValue(0,4); - getField("ChannelType").setValue(0,5); - getField("ChannelType").setValue(0,6); - getField("ChannelType").setValue(0,7); + getField("ChannelType").setValue("PWM",0); + getField("ChannelType").setValue("PWM",1); + getField("ChannelType").setValue("PWM",2); + getField("ChannelType").setValue("PWM",3); + getField("ChannelType").setValue("PWM",4); + getField("ChannelType").setValue("PWM",5); + getField("ChannelType").setValue("PWM",6); + getField("ChannelType").setValue("PWM",7); getField("ChannelAddr").setValue(0,0); getField("ChannelAddr").setValue(1,1); getField("ChannelAddr").setValue(2,2); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java index 19e477b62..6af673930 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java @@ -121,7 +121,7 @@ public class BatterySettings extends UAVDataObject { { getField("BatteryVoltage").setValue(11.1); getField("BatteryCapacity").setValue(2200); - getField("BatteryType").setValue(0); + getField("BatteryType").setValue("LiPo"); getField("Calibrations").setValue(1,0); getField("Calibrations").setValue(1,1); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java index 2e453eda5..fdc5bfcb0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java @@ -104,7 +104,7 @@ public class FlightPlanControl extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Command").setValue(0); + getField("Command").setValue("Start"); } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java index 00920553c..2303514c0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java @@ -144,8 +144,8 @@ public class FlightPlanStatus extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Status").setValue(0); - getField("ErrorType").setValue(0); + getField("Status").setValue("Stopped"); + getField("ErrorType").setValue("None"); getField("Debug1").setValue(0); getField("Debug2").setValue(0); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java index 2cde12f64..2fe8bb437 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java @@ -142,7 +142,7 @@ public class GuidanceSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("GuidanceMode").setValue(0); + getField("GuidanceMode").setValue("DUAL_LOOP"); getField("HorizontalP").setValue(0.2,0); getField("HorizontalP").setValue(150,1); getField("HorizontalVelPID").setValue(0.1,0); @@ -155,7 +155,7 @@ public class GuidanceSettings extends UAVDataObject { getField("VerticalVelPID").setValue(0,1); getField("VerticalVelPID").setValue(0,2); getField("VerticalVelPID").setValue(0,3); - getField("ThrottleControl").setValue(0); + getField("ThrottleControl").setValue("FALSE"); getField("MaxRollPitch").setValue(10); getField("UpdatePeriod").setValue(100); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java index 2adebce70..5941c069c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -139,7 +139,7 @@ public class HomeLocation extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Set").setValue(0); + getField("Set").setValue("FALSE"); getField("Latitude").setValue(0); getField("Longitude").setValue(0); getField("Altitude").setValue(0); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java index c14aef758..83697999a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -309,28 +309,28 @@ public class ManualControlSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("InputMode").setValue(0); - getField("Roll").setValue(0); - getField("Pitch").setValue(1); - getField("Yaw").setValue(2); - getField("Throttle").setValue(3); - getField("FlightMode").setValue(4); - getField("Accessory1").setValue(8); - getField("Accessory2").setValue(8); - getField("Accessory3").setValue(8); - getField("Arming").setValue(0); - getField("Stabilization1Settings").setValue(2,0); - getField("Stabilization1Settings").setValue(2,1); - getField("Stabilization1Settings").setValue(2,2); - getField("Stabilization2Settings").setValue(2,0); - getField("Stabilization2Settings").setValue(2,1); - getField("Stabilization2Settings").setValue(2,2); - getField("Stabilization3Settings").setValue(2,0); - getField("Stabilization3Settings").setValue(2,1); - getField("Stabilization3Settings").setValue(2,2); - getField("FlightModePosition").setValue(0,0); - getField("FlightModePosition").setValue(1,1); - getField("FlightModePosition").setValue(2,2); + getField("InputMode").setValue("PWM"); + getField("Roll").setValue("Channel1"); + getField("Pitch").setValue("Channel2"); + getField("Yaw").setValue("Channel3"); + getField("Throttle").setValue("Channel4"); + getField("FlightMode").setValue("Channel5"); + getField("Accessory1").setValue("None"); + getField("Accessory2").setValue("None"); + getField("Accessory3").setValue("None"); + getField("Arming").setValue("Always Disarmed"); + getField("Stabilization1Settings").setValue("Attitude",0); + getField("Stabilization1Settings").setValue("Attitude",1); + getField("Stabilization1Settings").setValue("Attitude",2); + getField("Stabilization2Settings").setValue("Attitude",0); + getField("Stabilization2Settings").setValue("Attitude",1); + getField("Stabilization2Settings").setValue("Attitude",2); + getField("Stabilization3Settings").setValue("Attitude",0); + getField("Stabilization3Settings").setValue("Attitude",1); + getField("Stabilization3Settings").setValue("Attitude",2); + getField("FlightModePosition").setValue("Manual",0); + getField("FlightModePosition").setValue("Manual",1); + getField("FlightModePosition").setValue("Manual",2); getField("ChannelMax").setValue(2000,0); getField("ChannelMax").setValue(2000,1); getField("ChannelMax").setValue(2000,2); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java index 554e366f3..9aa87d49e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java @@ -270,49 +270,49 @@ public class MixerSettings extends UAVDataObject { getField("ThrottleCurve2").setValue(0.5,2); getField("ThrottleCurve2").setValue(0.75,3); getField("ThrottleCurve2").setValue(1,4); - getField("Mixer1Type").setValue(0); + getField("Mixer1Type").setValue("Disabled"); getField("Mixer1Vector").setValue(0,0); getField("Mixer1Vector").setValue(0,1); getField("Mixer1Vector").setValue(0,2); getField("Mixer1Vector").setValue(0,3); getField("Mixer1Vector").setValue(0,4); - getField("Mixer2Type").setValue(0); + getField("Mixer2Type").setValue("Disabled"); getField("Mixer2Vector").setValue(0,0); getField("Mixer2Vector").setValue(0,1); getField("Mixer2Vector").setValue(0,2); getField("Mixer2Vector").setValue(0,3); getField("Mixer2Vector").setValue(0,4); - getField("Mixer3Type").setValue(0); + getField("Mixer3Type").setValue("Disabled"); getField("Mixer3Vector").setValue(0,0); getField("Mixer3Vector").setValue(0,1); getField("Mixer3Vector").setValue(0,2); getField("Mixer3Vector").setValue(0,3); getField("Mixer3Vector").setValue(0,4); - getField("Mixer4Type").setValue(0); + getField("Mixer4Type").setValue("Disabled"); getField("Mixer4Vector").setValue(0,0); getField("Mixer4Vector").setValue(0,1); getField("Mixer4Vector").setValue(0,2); getField("Mixer4Vector").setValue(0,3); getField("Mixer4Vector").setValue(0,4); - getField("Mixer5Type").setValue(0); + getField("Mixer5Type").setValue("Disabled"); getField("Mixer5Vector").setValue(0,0); getField("Mixer5Vector").setValue(0,1); getField("Mixer5Vector").setValue(0,2); getField("Mixer5Vector").setValue(0,3); getField("Mixer5Vector").setValue(0,4); - getField("Mixer6Type").setValue(0); + getField("Mixer6Type").setValue("Disabled"); getField("Mixer6Vector").setValue(0,0); getField("Mixer6Vector").setValue(0,1); getField("Mixer6Vector").setValue(0,2); getField("Mixer6Vector").setValue(0,3); getField("Mixer6Vector").setValue(0,4); - getField("Mixer7Type").setValue(0); + getField("Mixer7Type").setValue("Disabled"); getField("Mixer7Vector").setValue(0,0); getField("Mixer7Vector").setValue(0,1); getField("Mixer7Vector").setValue(0,2); getField("Mixer7Vector").setValue(0,3); getField("Mixer7Vector").setValue(0,4); - getField("Mixer8Type").setValue(0); + getField("Mixer8Type").setValue("Disabled"); getField("Mixer8Vector").setValue(0,0); getField("Mixer8Vector").setValue(0,1); getField("Mixer8Vector").setValue(0,2); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java index 9136627f4..e9313472c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -121,22 +121,22 @@ public class SystemAlarms extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Alarm").setValue(0,0); - getField("Alarm").setValue(0,1); - getField("Alarm").setValue(0,2); - getField("Alarm").setValue(0,3); - getField("Alarm").setValue(0,4); - getField("Alarm").setValue(0,5); - getField("Alarm").setValue(0,6); - getField("Alarm").setValue(0,7); - getField("Alarm").setValue(0,8); - getField("Alarm").setValue(0,9); - getField("Alarm").setValue(0,10); - getField("Alarm").setValue(0,11); - getField("Alarm").setValue(0,12); - getField("Alarm").setValue(0,13); - getField("Alarm").setValue(0,14); - getField("Alarm").setValue(0,15); + getField("Alarm").setValue("Uninitialised",0); + getField("Alarm").setValue("Uninitialised",1); + getField("Alarm").setValue("Uninitialised",2); + getField("Alarm").setValue("Uninitialised",3); + getField("Alarm").setValue("Uninitialised",4); + getField("Alarm").setValue("Uninitialised",5); + getField("Alarm").setValue("Uninitialised",6); + getField("Alarm").setValue("Uninitialised",7); + getField("Alarm").setValue("Uninitialised",8); + getField("Alarm").setValue("Uninitialised",9); + getField("Alarm").setValue("Uninitialised",10); + getField("Alarm").setValue("Uninitialised",11); + getField("Alarm").setValue("Uninitialised",12); + getField("Alarm").setValue("Uninitialised",13); + getField("Alarm").setValue("Uninitialised",14); + getField("Alarm").setValue("Uninitialised",15); } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java index d01b55b24..99bceb6ba 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java @@ -117,7 +117,7 @@ public class SystemSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("AirframeType").setValue(0); + getField("AirframeType").setValue("FixedWing"); } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java index 6995a02b0..675f9b592 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java @@ -108,7 +108,7 @@ public class TelemetrySettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Speed").setValue(5); + getField("Speed").setValue("57600"); } From 7d13f4869d60195b2ec69c3962479c4a9a3fa4f4 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 7 Mar 2011 04:54:43 -0600 Subject: [PATCH 211/543] Made a lot of critical functions synchronized to block race conditions (essentialy implements a mutex locker for that object). Also added callbacks to UAVObjects for unpacked and updated. More to come. Finally test case that checks that we get FlightStatus through UAVTalk (i.e. that the aircraft is talking). --- .../src/org/openpilot/uavtalk/UAVObject.java | 49 +++++++++++++++++-- .../org/openpilot/uavtalk/UAVObjectField.java | 18 +++---- .../openpilot/uavtalk/UAVObjectManager.java | 14 +++--- .../src/org/openpilot/uavtalk/UAVTalk.java | 18 ++++++- .../tests/org/openpilot/uavtalk/TalkTest.java | 33 +++++++++++-- 5 files changed, 107 insertions(+), 25 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index a990def2c..6ede86094 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -3,9 +3,50 @@ package org.openpilot.uavtalk; import java.nio.ByteBuffer; import java.util.List; import java.util.ListIterator; +import java.util.Observer; +import java.util.Observable; public abstract class UAVObject { + public class CallbackListener extends Observable { + private UAVObject parent; + + public CallbackListener(UAVObject parent) { + this.parent = parent; + } + + public void event () { + setChanged(); + notifyObservers(parent); + } + } + + private CallbackListener updatedListeners = new CallbackListener(this); + public void addUpdatedObserver(Observer o) { + synchronized(updatedListeners) { + updatedListeners.addObserver(o); + } + } + void updated() { + synchronized(updatedListeners) { + updatedListeners.event(); + } + } + + private CallbackListener unpackedListeners = new CallbackListener(this); + public void addUnpackedObserver(Observer o) { + synchronized(unpackedListeners) { + unpackedListeners.addObserver(o); + } + } + void unpacked() { + synchronized(unpackedListeners) { + System.out.println("Unpacked!: " + unpackedListeners.countObservers() + " " + getName()); + unpackedListeners.event(); + } + } + + /** * Object update mode */ @@ -298,10 +339,12 @@ public abstract class UAVObject { UAVObjectField field = li.next(); numBytes += field.unpack(dataIn); } + + // Trigger all the listeners for the unpack event + unpacked(); + updated(); + return numBytes; - // TODO: Callbacks - // emit objectUnpacked(this); // trigger object updated event - // emit objectUpdated(this); } // /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 0b72c33c8..21444a04b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -91,8 +91,7 @@ public class UAVObjectField { * @param dataOut * @return the number of bytes added **/ - public int pack(ByteBuffer dataOut) { - //QMutexLocker locker(obj->getMutex()); + public synchronized int pack(ByteBuffer dataOut) { // Pack each element in output buffer dataOut.order(ByteOrder.LITTLE_ENDIAN); switch (type) @@ -153,7 +152,7 @@ public class UAVObjectField { return getNumBytes(); } - public int unpack(ByteBuffer dataIn) { + public synchronized int unpack(ByteBuffer dataIn) { // Unpack each element from input buffer dataIn.order(ByteOrder.LITTLE_ENDIAN); switch (type) @@ -240,10 +239,9 @@ public class UAVObjectField { return getNumBytes(); } - Object getValue() { return getValue(0); }; + public Object getValue() { return getValue(0); }; @SuppressWarnings("unchecked") - Object getValue(int index) { -// QMutexLocker locker(obj->getMutex()); + public synchronized Object getValue(int index) { // Check that index is not out of bounds if ( index >= numElements ) { @@ -287,8 +285,7 @@ public class UAVObjectField { public void setValue(Object data) { setValue(data,0); } @SuppressWarnings("unchecked") - public void setValue(Object data, int index) { - // QMutexLocker locker(obj->getMutex()); + public synchronized void setValue(Object data, int index) { // Check that index is not out of bounds //if ( index >= numElements ); //throw new Exception("Index out of bounds"); @@ -361,6 +358,7 @@ public class UAVObjectField { //throw new Exception("Sorry I haven't implemented strings yet"); } } + obj.updated(); } } @@ -449,7 +447,7 @@ public class UAVObjectField { } @SuppressWarnings("unchecked") - public void clear() { + public synchronized void clear() { switch (type) { case INT8: @@ -503,7 +501,7 @@ public class UAVObjectField { } } - public void constructorInitialize(String name, String units, FieldType type, List elementNames, List options) { + public synchronized void constructorInitialize(String name, String units, FieldType type, List elementNames, List options) { // Copy params this.name = name; this.units = units; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 2e531fc85..74ddb95fb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -23,7 +23,7 @@ public class UAVObjectManager { * updates. * @throws Exception */ - public boolean registerObject(UAVDataObject obj) throws Exception + public synchronized boolean registerObject(UAVDataObject obj) throws Exception { // QMutexLocker locker(mutex); @@ -128,7 +128,7 @@ public class UAVObjectManager { return true; } - public void addObject(UAVObject obj) + public synchronized void addObject(UAVObject obj) { // Add to list List ls = new ArrayList(); @@ -143,15 +143,15 @@ public class UAVObjectManager { */ public List> getObjects() { - //QMutexLocker locker(mutex); return objects; } /** * Same as getObjects() but will only return DataObjects. */ - public List< List > getDataObjects() + public List< List > getDataObjects() { + assert(false); // TOOD This return new ArrayList>(); /* QMutexLocker locker(mutex); @@ -190,6 +190,7 @@ public class UAVObjectManager { */ public List > getMetaObjects() { + assert(false); // TODO return new ArrayList< List >(); /* QMutexLocker locker(mutex); @@ -267,7 +268,7 @@ public class UAVObjectManager { /** * Helper function for the public getObject() functions. */ - public UAVObject getObject(String name, int objId, int instId) + public synchronized UAVObject getObject(String name, int objId, int instId) { //QMutexLocker locker(mutex); // Check if this object type is already in the list @@ -310,9 +311,8 @@ public class UAVObjectManager { /** * Helper function for the public getObjectInstances() */ - public List getObjectInstances(String name, int objId) + public synchronized List getObjectInstances(String name, int objId) { - //QMutexLocker locker(mutex); // Check if this object type is already in the list ListIterator> objIter = objects.listIterator(); while(objIter.hasNext()) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 07b061bc9..7ea9c7c60 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -10,6 +10,22 @@ import java.nio.ByteOrder; public class UAVTalk { + private Thread inputProcessingThread = null; + /** + * A reference to the thread for processing the incoming stream + * @return + */ + public Thread getInputProcessThread() { + if(inputProcessingThread == null) + + inputProcessingThread = new Thread() { + public void run() { + processInputStream(); + } + }; + return inputProcessingThread; + } + /** * Constants */ @@ -684,7 +700,7 @@ public class UAVTalk { * \param[in] type Transaction type * \return Success (true), Failure (false) */ - public boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) + public synchronized boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) { int length; int dataOffset; diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java index 6dc23530e..252927122 100644 --- a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java +++ b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java @@ -9,6 +9,8 @@ import java.net.DatagramSocket; import java.net.InetAddress; import java.net.Socket; import java.nio.ByteBuffer; +import java.util.Observable; +import java.util.Observer; import org.junit.BeforeClass; import org.junit.Test; @@ -20,8 +22,9 @@ public class TalkTest { static UAVObjectManager objMngr; static final String IP_ADDRDESS = new String("127.0.0.1"); - static final int PORT_NUM = 8000; - + static final int PORT_NUM = 7777; + boolean succeed = false; + @BeforeClass public static void setUpBeforeClass() throws Exception { objMngr = new UAVObjectManager(); @@ -29,7 +32,7 @@ public class TalkTest { } @Test - public void testProcessInputStream() { + public void testGetFlightStatus() { Socket connection = null; UAVTalk talk = null; try{ @@ -48,7 +51,29 @@ public class TalkTest { fail("Couldn't construct UAVTalk object"); } - talk.processInputStream(); + Thread inputStream = talk.getInputProcessThread(); + inputStream.start(); + + succeed = false; + + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + + obj.addUpdatedObserver( new Observer() { + public void update(Observable observable, Object data) { + // TODO Auto-generated method stub + System.out.println("Updated: " + data.toString()); + succeed = true; + } + }); + + try { + Thread.sleep(1000); + } catch (InterruptedException e1) { + } + + if(!succeed) + fail("Never received a FlightTelemetryStats update"); + } @Test From b81450a4aa8a22e1d357c4182d27f805968ffb2e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 7 Mar 2011 04:56:14 -0600 Subject: [PATCH 212/543] Test case for the callbacks --- .../org/openpilot/uavtalk/DataObjectTest.java | 95 +++++++++++++++++++ 1 file changed, 95 insertions(+) create mode 100644 androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java diff --git a/androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java b/androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java new file mode 100644 index 000000000..0f8106cc5 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java @@ -0,0 +1,95 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import java.nio.ByteBuffer; +import java.util.Observer; + +import org.junit.BeforeClass; +import org.junit.Test; +import org.openpilot.uavtalk.uavobjects.ActuatorCommand; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; + +import android.database.Observable; + +public class DataObjectTest { + + boolean succeed = false; + + @BeforeClass + public static void setUpBeforeClass() throws Exception { + } + + @Test + public void testUpdatedObserver() { + + succeed = false; + + UAVObject obj = new ActuatorCommand(); + obj.addUpdatedObserver( new Observer() { + + public void update(java.util.Observable observable, Object data) { + System.out.println("Updated: " + data.toString()); + succeed = true; + } + }); + obj.updated(); + + if(!succeed) + fail("No callback"); + + System.out.println("Done"); + + } + + @Test + public void testUpdatedViaObjMngr() { + succeed = false; + + UAVObjectManager objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + obj.addUpdatedObserver( new Observer() { + + public void update(java.util.Observable observable, Object data) { + System.out.println("Updated: " + data.toString()); + succeed = true; + } + }); + objMngr.getObject("FlightTelemetryStats").updated(); + + if(!succeed) + fail("No callback"); + System.out.println("Done"); + + } + + @Test + public void testUnpackedViaObjMngr() { + succeed = false; + + UAVObjectManager objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + obj.addUnpackedObserver( new Observer() { + + public void update(java.util.Observable observable, Object data) { + System.out.println("Updated: " + data.toString()); + succeed = true; + } + }); + + ByteBuffer bbuf = ByteBuffer.allocate(obj.getNumBytes()); + objMngr.getObject("FlightTelemetryStats").unpack(bbuf); + + if(!succeed) + fail("No callback"); + + System.out.println("Done"); + + } + + +} From 157e5619273a2681284322b16c3025e4135245ac Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 7 Mar 2011 11:26:50 -0600 Subject: [PATCH 213/543] Add isMetadata() instead of testing whether dynamic cast fails --- androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java | 1 + androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java | 5 +++++ androidgcs/src/org/openpilot/uavtalk/UAVObject.java | 1 + 3 files changed, 7 insertions(+) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index de04f81c5..5694cc9d8 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -24,6 +24,7 @@ public abstract class UAVDataObject extends UAVObject { super.initialize(instID); } + public boolean isMetadata() { return true; }; /** * Assign a metaobject */ diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index 98e4bd626..7aab176ef 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -66,6 +66,11 @@ public class UAVMetaObject extends UAVObject { // Setup metadata of parent parentMetadata = parent.getDefaultMetadata(); } + + @Override + public boolean isMetadata() { + return true; + }; /** * Get the parent object diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 6ede86094..6d35df822 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -46,6 +46,7 @@ public abstract class UAVObject { } } + public abstract boolean isMetadata(); /** * Object update mode From 943dd82a7587b26aa391dd869f92a0ec1e4f835c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 7 Mar 2011 11:27:21 -0600 Subject: [PATCH 214/543] Initial start of the telemetry system which interfaces between UAVTalk and the ObjectManager/Objects --- .../src/org/openpilot/uavtalk/Telemetry.java | 25 ++ .../openpilot/uavtalk/TelemetryManager.java | 5 + .../openpilot/uavtalk/TelemetryMonitor.java | 263 ++++++++++++++++++ 3 files changed, 293 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/Telemetry.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/TelemetryManager.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java new file mode 100644 index 000000000..88bc33de5 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -0,0 +1,25 @@ +package org.openpilot.uavtalk; + +public class Telemetry { + + private TelemetryStats stats; + public class TelemetryStats { + public int txBytes; + public int rxBytes; + public int txObjectBytes; + public int rxObjectBytes; + public int rxObjects; + public int txObjects; + public int txErrors; + public int rxErrors; + public int txRetries; + } ; + + public TelemetryStats getStats() { + return stats; + } + + public void resetStats() { + stats = new TelemetryStats(); + } +} diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryManager.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryManager.java new file mode 100644 index 000000000..7540a1423 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryManager.java @@ -0,0 +1,5 @@ +package org.openpilot.uavtalk; + +public class TelemetryManager { + +} diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java new file mode 100644 index 000000000..40fc220cc --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -0,0 +1,263 @@ +package org.openpilot.uavtalk; + +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; +import java.util.Observable; +import java.util.Observer; +import java.util.Timer; +import java.util.TimerTask; + +import org.openpilot.uavtalk.uavobjects.FlightTelemetryStats; +import org.openpilot.uavtalk.uavobjects.GCSTelemetryStats; + +import android.util.Log; + +public class TelemetryMonitor { + + private static final String TAG = "TelemetryMonitor"; + + static final int STATS_UPDATE_PERIOD_MS = 4000; + static final int STATS_CONNECT_PERIOD_MS = 1000; + static final int CONNECTION_TIMEOUT_MS = 8000; + + private UAVObjectManager objMngr; + private Telemetry tel; + private UAVObject objPending; + private UAVObject gcsStatsObj; + private UAVObject flightStatsObj; + private Timer periodicTask; + private int currentPeriod; + private List queue; + + public TelemetryMonitor(UAVObjectManager objMngr, Telemetry tel) + { + this.objMngr = objMngr; + this.tel = tel; + this.objPending = null; + queue = new ArrayList(); + + // Get stats objects + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); + flightStatsObj = objMngr.getObject("FlightTelemetryStats"); + + flightStatsObj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + flightStatsUpdated((UAVObject) data); + } + }); + + // Start update timer + setPeriod(STATS_CONNECT_PERIOD_MS); + } + + /** + * Initiate object retrieval, initialize queue with objects to be retrieved. + */ + public void startRetrievingObjects() + { + // Clear object queue + queue.clear(); + // Get all objects, add metaobjects, settings and data objects with OnChange update mode to the queue + List< List > objs = objMngr.getObjects(); + + ListIterator> objListIterator = objs.listIterator(); + while( objListIterator.hasNext() ) + { + List instList = objListIterator.next(); + UAVObject obj = instList.get(0); + UAVObject.Metadata mdata = obj.getMetadata(); + if ( mdata.gcsTelemetryUpdateMode != UAVObject.UpdateMode.UPDATEMODE_NEVER ) + { + if ( obj.isMetadata() ) + { + queue.add(obj); + } + else /* Data object */ + { + UAVDataObject dobj = (UAVDataObject) obj; + if ( dobj.isSettings() ) + { + queue.add(obj); + } + else + { + if ( mdata.flightTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) + { + queue.add(obj); + } + } + } + } + } + // Start retrieving + Log.d(TAG,"Starting to retrieve meta and settings objects from the autopilot (%1 objects)" + queue.size()) ; + retrieveNextObject(); + } + + /** + * Cancel the object retrieval + */ + public void stopRetrievingObjects() + { + //qxtLog->debug("Object retrieval has been cancelled"); + queue.clear(); + } + + /** + * Retrieve the next object in the queue + */ + public void retrieveNextObject() + { + // If queue is empty return + if ( queue.isEmpty() ) + { + //qxtLog->debug("Object retrieval completed"); + //emit connected(); + return; + } + // Get next object from the queue + UAVObject obj = queue.remove(0); + + Log.d(TAG, "Retrieving object: " + obj.getName()) ; + // Connect to object + //connect(obj, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(transactionCompleted(UAVObject*,bool))); + // Request update + obj.requestUpdate(); + objPending = obj; + } + + /** + * Called by the retrieved object when a transaction is completed. + */ + public void transactionCompleted(UAVObject obj, boolean success) + { + //QMutexLocker locker(mutex); + // Disconnect from sending object + //obj->disconnect(this); + objPending = null; + + // Process next object if telemetry is still available + if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) + { + retrieveNextObject(); + } + else + { + stopRetrievingObjects(); + } + } + + /** + * Called each time the flight stats object is updated by the autopilot + */ + public synchronized void flightStatsUpdated(UAVObject obj) + { + // Force update if not yet connected + if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 || + ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) + { + processStatsUpdates(); + } + } + + /** + * Called periodically to update the statistics and connection status. + */ + public synchronized void processStatsUpdates() + { + // Get telemetry stats + Telemetry.TelemetryStats telStats = tel.getStats(); + tel.resetStats(); + + // Update stats object + gcsStatsObj.getField("RxDataRate").setDouble( (float)telStats.rxBytes / ((float)currentPeriod/1000.0) ); + gcsStatsObj.getField("TxDataRate").setDouble( (float)telStats.txBytes / ((float)currentPeriod/1000.0) ); + UAVObjectField field = gcsStatsObj.getField("RxFailures"); + field.setDouble(field.getDouble() + telStats.rxErrors); + field = gcsStatsObj.getField("TxFailures"); + field.setDouble(field.getDouble() + telStats.txErrors); + field = gcsStatsObj.getField("TxRetries"); + field.setDouble(field.getDouble() + telStats.txRetries); + + // Check for a connection timeout + boolean connectionTimeout; + if ( telStats.rxObjects > 0 ) + { + //connectionTimer.start(); + } + if ( connectionTimer.elapsed() > CONNECTION_TIMEOUT_MS ) + { + connectionTimeout = true; + } + else + { + connectionTimeout = false; + } + + // Update connection state + int oldStatus = gcsStats.Status; + if ( gcsStats.Status == GCSTelemetryStats::STATUS_DISCONNECTED ) + { + // Request connection + gcsStats.Status = GCSTelemetryStats::STATUS_HANDSHAKEREQ; + } + else if ( gcsStats.Status == GCSTelemetryStats::STATUS_HANDSHAKEREQ ) + { + // Check for connection acknowledge + if ( flightStats.Status == FlightTelemetryStats::STATUS_HANDSHAKEACK ) + { + gcsStats.Status = GCSTelemetryStats::STATUS_CONNECTED; + } + } + else if ( gcsStats.Status == GCSTelemetryStats::STATUS_CONNECTED ) + { + // Check if the connection is still active and the the autopilot is still connected + if (flightStats.Status == FlightTelemetryStats::STATUS_DISCONNECTED || connectionTimeout) + { + gcsStats.Status = GCSTelemetryStats::STATUS_DISCONNECTED; + } + } + + // Set data + gcsStatsObj->setData(gcsStats); + + // Force telemetry update if not yet connected + if ( gcsStats.Status != GCSTelemetryStats::STATUS_CONNECTED || + flightStats.Status != FlightTelemetryStats::STATUS_CONNECTED ) + { + gcsStatsObj->updated(); + } + + // Act on new connections or disconnections + if (gcsStats.Status == GCSTelemetryStats::STATUS_CONNECTED && gcsStats.Status != oldStatus) + { + setPeriod(STATS_UPDATE_PERIOD_MS); + statsTimer->setInterval(STATS_UPDATE_PERIOD_MS); + Log.d(TAG,"Connection with the autopilot established"); + startRetrievingObjects(); + } + if (gcsStats.Status == GCSTelemetryStats::STATUS_DISCONNECTED && gcsStats.Status != oldStatus) + { + setPeriod(STATS_CONNECT_PERIOD_MS); + Log.d(TAG,"Connection with the autopilot lost"); + Log.d(TAG,"Trying to connect to the autopilot"); + emit disconnected(); + } + } + + private void setPeriod(int ms) { + if(periodicTask == null) + periodicTask = new Timer(); + + periodicTask.cancel(); + currentPeriod = ms; + periodicTask.scheduleAtFixedRate(new TimerTask() { + @Override + public void run() { + processStatsUpdates(); + } + }, currentPeriod, currentPeriod); + } + +} From 63f750c51e05d4e0b1c9f06db3ff32c0d3fb16fb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 9 Mar 2011 02:44:25 -0600 Subject: [PATCH 215/543] A few more synchronized statements and deep cloning of objects --- .../src/org/openpilot/uavtalk/UAVObject.java | 30 ++-- .../org/openpilot/uavtalk/UAVObjectField.java | 13 +- .../openpilot/uavtalk/UAVObjectManager.java | 130 +++++++++--------- 3 files changed, 97 insertions(+), 76 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 6d35df822..adfece03e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -1,6 +1,7 @@ package org.openpilot.uavtalk; import java.nio.ByteBuffer; +import java.util.ArrayList; import java.util.List; import java.util.ListIterator; import java.util.Observer; @@ -128,8 +129,7 @@ public abstract class UAVObject { // this.mutex = new QMutex(QMutex::Recursive); }; - public void initialize(int instID) { - // QMutexLocker locker(mutex); + public synchronized void initialize(int instID) { this.instID = instID; } @@ -146,9 +146,8 @@ public abstract class UAVObject { * @throws Exception * When unable to unpack a field */ - public void initializeFields(List fields, ByteBuffer data, + public synchronized void initializeFields(List fields, ByteBuffer data, int numBytes) { - // TODO: QMutexLocker locker(mutex); this.numBytes = numBytes; this.fields = fields; // Initialize fields @@ -267,15 +266,13 @@ public abstract class UAVObject { * Get the number of fields held by this object */ public int getNumFields() { - // QMutexLocker locker(mutex); return fields.size(); } /** * Get the object's fields */ - public List getFields() { - // QMutexLocker locker(mutex); + public synchronized List getFields() { return fields; } @@ -286,7 +283,6 @@ public abstract class UAVObject { * @returns The field or NULL if not found */ public UAVObjectField getField(String name) { - // QMutexLocker locker(mutex); // Look for field ListIterator li = fields.listIterator(); while (li.hasNext()) { @@ -307,8 +303,7 @@ public abstract class UAVObject { * @returns The number of bytes copied * @note The array must already have enough space allocated for the object */ - public int pack(ByteBuffer dataOut) throws Exception { - // QMutexLocker locker(mutex); + public synchronized int pack(ByteBuffer dataOut) throws Exception { if (dataOut.remaining() < getNumBytes()) throw new Exception("Not enough bytes in ByteBuffer to pack object"); int numBytes = 0; @@ -329,7 +324,7 @@ public abstract class UAVObject { * @throws Exception * @returns The number of bytes copied */ - public int unpack(ByteBuffer dataIn) { + public synchronized int unpack(ByteBuffer dataIn) { if( dataIn == null ) return 0; @@ -532,8 +527,17 @@ public abstract class UAVObject { /** * Java specific functions */ - public UAVObject clone() { - return (UAVObject) clone(); + public synchronized UAVObject clone() { + UAVObject newObj = clone(); + List newFields = new ArrayList(); + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField nf = li.next().clone(); + nf.initialize(newObj); + newFields.add(nf); + } + newObj.initializeFields(newFields, ByteBuffer.allocate(numBytes), numBytes); + return newObj; } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 21444a04b..2fd7f7846 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -617,6 +617,17 @@ public class UAVObjectField { return num; } + + @Override + public UAVObjectField clone() + { + UAVObjectField newField = new UAVObjectField(new String(name), new String(units), type, + new ArrayList(elementNames), + new ArrayList(options)); + newField.initialize(obj); + newField.data = data; + return newField; + } private String name; private String units; @@ -626,7 +637,7 @@ public class UAVObjectField { private int numElements; private int numBytesPerElement; private int offset; - private Object data; private UAVObject obj; + protected Object data; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 74ddb95fb..63f535eac 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -3,9 +3,29 @@ package org.openpilot.uavtalk; import java.util.ArrayList; import java.util.List; import java.util.ListIterator; +import java.util.Observable; +import java.util.Observer; public class UAVObjectManager { + public class CallbackListener extends Observable { + public void event (UAVObject obj) { + setChanged(); + notifyObservers(obj); + } + } + private CallbackListener newInstance = new CallbackListener(); + public void addNewInstanceObserver(Observer o) { + synchronized(newInstance) { + newInstance.addObserver(o); + } + } + private CallbackListener newObject = new CallbackListener(); + public void addNewObjectObserver(Observer o) { + synchronized(newObject) { + newObject.addObserver(o); + } + } private final int MAX_INSTANCES = 10; // Use array list to store objects since rarely added or deleted @@ -79,11 +99,12 @@ public class UAVObjectManager { UAVDataObject newObj = obj.clone(instID); newObj.initialize(mobj); instList.add(newObj); - // emit new instance signal + newInstance.event(newObj); } obj.initialize(mobj); //emit new instance signal instList.add(obj); + newInstance.event(obj); instIter = instList.listIterator(); while(instIter.hasNext()) { @@ -101,13 +122,13 @@ public class UAVObjectManager { UAVDataObject cobj = obj.clone(instId); cobj.initialize(mobj); instList.add(cobj); - // emit newInstance(cobj); + newInstance.event(cobj); } // Finally, initialize the actual object instance obj.initialize(mobj); // Add the actual object instance in the list instList.add(obj); - //emit newInstance(obj); + newInstance.event(obj); return true; } @@ -149,81 +170,67 @@ public class UAVObjectManager { /** * Same as getObjects() but will only return DataObjects. */ - public List< List > getDataObjects() + public synchronized List< List > getDataObjects() { - assert(false); // TOOD This - return new ArrayList>(); - - /* QMutexLocker locker(mutex); - QList< QList > dObjects; + List< List > dObjects = new ArrayList< List > (); // Go through objects and copy to new list when types match - for (int objidx = 0; objidx < objects.length(); ++objidx) - { - if (objects[objidx].length() > 0) - { - // Check type - UAVDataObject* obj = dynamic_cast(objects[objidx][0]); - if (obj != NULL) - { - // Create instance list - QList list; - // Go through instances and cast them to UAVDataObject, then add to list - for (int instidx = 0; instidx < objects[objidx].length(); ++instidx) - { - obj = dynamic_cast(objects[objidx][instidx]); - if (obj != NULL) - { - list.append(obj); - } - } - // Append to object list - dObjects.append(list); - } + ListIterator> objIt = objects.listIterator(0); + + // Check if this object type is already in the list + while(objIt.hasNext()) { + List instList = objIt.next(); + + // If no instances skip + if(instList.size() == 0) + continue; + + // If meta data skip + if(instList.get(0).isMetadata()) + continue; + + List newInstList = new ArrayList(); + ListIterator instIt = instList.listIterator(); + while(instIt.hasNext()) { + newInstList.add((UAVDataObject) instIt.next()); } - }*/ + dObjects.add(newInstList); + } // Done + return dObjects; } /** * Same as getObjects() but will only return MetaObjects. */ - public List > getMetaObjects() + public synchronized List > getMetaObjects() { - assert(false); // TODO - return new ArrayList< List >(); - /* - QMutexLocker locker(mutex); - QList< QList > mObjects; + List< List > mObjects = new ArrayList< List > (); // Go through objects and copy to new list when types match - for (int objidx = 0; objidx < objects.length(); ++objidx) - { - if (objects[objidx].length() > 0) - { - // Check type - UAVMetaObject* obj = dynamic_cast(objects[objidx][0]); - if (obj != NULL) - { - // Create instance list - QList list; - // Go through instances and cast them to UAVMetaObject, then add to list - for (int instidx = 0; instidx < objects[objidx].length(); ++instidx) - { - obj = dynamic_cast(objects[objidx][instidx]); - if (obj != NULL) - { - list.append(obj); - } - } - // Append to object list - mObjects.append(list); - } + ListIterator> objIt = objects.listIterator(0); + + // Check if this object type is already in the list + while(objIt.hasNext()) { + List instList = objIt.next(); + + // If no instances skip + if(instList.size() == 0) + continue; + + // If meta data skip + if(!instList.get(0).isMetadata()) + continue; + + List newInstList = new ArrayList(); + ListIterator instIt = instList.listIterator(); + while(instIt.hasNext()) { + newInstList.add((UAVMetaObject) instIt.next()); } + mObjects.add(newInstList); } // Done return mObjects; - */ } @@ -270,7 +277,6 @@ public class UAVObjectManager { */ public synchronized UAVObject getObject(String name, int objId, int instId) { - //QMutexLocker locker(mutex); // Check if this object type is already in the list ListIterator> objIter = objects.listIterator(); while(objIter.hasNext()) { From 6bc97f1a3dedbba1e5c1d4e5bc28c6c2a21e3ca7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 02:05:36 -0600 Subject: [PATCH 216/543] Most of the work on Telemetry.java as well as lots of signals for various object events --- .../src/org/openpilot/uavtalk/Telemetry.java | 623 +++++++++++++++++- .../openpilot/uavtalk/TelemetryMonitor.java | 2 +- .../src/org/openpilot/uavtalk/UAVObject.java | 51 +- .../openpilot/uavtalk/UAVObjectManager.java | 3 +- .../src/org/openpilot/uavtalk/UAVTalk.java | 7 +- 5 files changed, 673 insertions(+), 13 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 88bc33de5..79e821fe3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -1,8 +1,18 @@ package org.openpilot.uavtalk; +import java.util.LinkedList; +import java.util.List; +import java.util.ListIterator; +import java.util.Observable; +import java.util.Observer; +import java.util.Queue; +import java.util.Timer; +import java.util.TimerTask; + +import org.openpilot.uavtalk.UAVObject.Acked; + public class Telemetry { - private TelemetryStats stats; public class TelemetryStats { public int txBytes; public int rxBytes; @@ -15,11 +25,612 @@ public class Telemetry { public int txRetries; } ; - public TelemetryStats getStats() { - return stats; - } + class ObjectTimeInfo { + UAVObject obj; + int updatePeriodMs; /** Update period in ms or 0 if no periodic updates are needed */ + int timeToNextUpdateMs; /** Time delay to the next update */ + }; + + class ObjectQueueInfo { + UAVObject obj; + int event; + boolean allInstances; + }; + + class ObjectTransactionInfo { + UAVObject obj; + boolean allInstances; + boolean objRequest; + int retriesRemaining; + Acked acked; + } ; - public void resetStats() { - stats = new TelemetryStats(); + /** + * Events generated by objects. Not enum because used in mask. + */ + private static final int EV_UNPACKED = 0x01; /** Object data updated by unpacking */ + private static final int EV_UPDATED = 0x02; /** Object data updated by changing the data structure */ + private static final int EV_UPDATED_MANUAL = 0x04; /** Object update event manually generated */ + private static final int EV_UPDATE_REQ = 0x08; /** Request to update object data */ + + /** + * Constructor + */ + public Telemetry(UAVTalk utalk, UAVObjectManager objMngr) + { + this.utalk = utalk; + this.objMngr = objMngr; + + // Process all objects in the list + List< List > objs = objMngr.getObjects(); + ListIterator> li = objs.listIterator(); + while(li.hasNext()) + registerObject(li.next().get(0)); // we only need to register one instance per object type + + // Listen to new object creations + objMngr.addNewInstanceObserver(new Observer() { + public void update(Observable observable, Object data) { + newInstance((UAVObject) data); + } + }); + objMngr.addNewObjectObserver(new Observer() { + public void update(Observable observable, Object data) { + newObject((UAVObject) data); + } + }); + + // Listen to transaction completions + utalk.addObserver(new Observer() { + public void update(Observable observable, Object data) { + transactionCompleted((UAVObject) data); + } + }); + + // Get GCS stats object + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); + + // Setup transaction timer + transPending = false; + transTimer = new Timer(); + transTimerTask = new TimerTask() { + @Override + public void run() { + transactionTimeout(); + } + }; + // Setup and start the periodic timer + timeToNextUpdateMs = 0; + + updateTimer = new Timer(); + updateTimerTask = new TimerTask() { + @Override + public void run() { + processPeriodicUpdates(); + } + }; + updateTimer.scheduleAtFixedRate(updateTimerTask, 1000, 1000); + // Setup and start the stats timer + txErrors = 0; + txRetries = 0; } + + /** + * Register a new object for periodic updates (if enabled) + */ + private void registerObject(UAVObject obj) + { + // Setup object for periodic updates + addObject(obj); + + // Setup object for telemetry updates + updateObject(obj); + } + + /** + * Add an object in the list used for periodic updates + */ + private void addObject(UAVObject obj) + { + // Check if object type is already in the list + ListIterator li = objList.listIterator(); + while(li.hasNext()) { + ObjectTimeInfo n = li.next(); + if( n.obj.getObjID() == obj.getObjID() ) + { + // Object type (not instance!) is already in the list, do nothing + return; + } + } + + // If this point is reached, then the object type is new, let's add it + ObjectTimeInfo timeInfo = new ObjectTimeInfo(); + timeInfo.obj = obj; + timeInfo.timeToNextUpdateMs = 0; + timeInfo.updatePeriodMs = 0; + objList.add(timeInfo); + } + + /** + * Update the object's timers + */ + private void setUpdatePeriod(UAVObject obj, int periodMs) + { + // Find object type (not instance!) and update its period + ListIterator li = objList.listIterator(); + while(li.hasNext()) { + ObjectTimeInfo n = li.next(); + if ( n.obj.getObjID() == obj.getObjID() ) + { + n.updatePeriodMs = periodMs; + n.timeToNextUpdateMs = (int) (periodMs * (new java.util.Random()).nextDouble()); // avoid bunching of updates + } + } + } + + /** + * Connect to all instances of an object depending on the event mask specified + */ + private void connectToObjectInstances(UAVObject obj, int eventMask) + { + List objs = objMngr.getObjectInstances(obj.getObjID()); + ListIterator li = objs.listIterator(); + while(li.hasNext()) + { + obj = li.next(); + //TODO: Disconnect all + // obj.disconnect(this); + + // Connect only the selected events + if ( (eventMask&EV_UNPACKED) != 0) + { + obj.addUnpackedObserver(new Observer() { + public void update(Observable observable, Object data) { + objectUnpacked( (UAVObject) data); + } + }); + } + if ( (eventMask&EV_UPDATED) != 0) + { + obj.addUpdatedAutoObserver(new Observer() { + public void update(Observable observable, Object data) { + objectUpdatedAuto( (UAVObject) data); + } + }); + } + if ( (eventMask&EV_UPDATED_MANUAL) != 0) + { + obj.addUpdatedManualObserver(new Observer() { + public void update(Observable observable, Object data) { + objectUpdatedManual( (UAVObject) data); + } + }); + } + if ( (eventMask&EV_UPDATE_REQ) != 0) + { + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + updateRequested( (UAVObject) data); + } + }); + } + } + } + + /** + * Update an object based on its metadata properties + */ + private void updateObject(UAVObject obj) + { + // Get metadata + UAVObject.Metadata metadata = obj.getMetadata(); + + // Setup object depending on update mode + int eventMask; + if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_PERIODIC ) + { + // Set update period + setUpdatePeriod(obj, metadata.gcsTelemetryUpdatePeriod); + // Connect signals for all instances + eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if(obj.isMetadata()) + eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) + + connectToObjectInstances(obj, eventMask); + } + else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) + { + // Set update period + setUpdatePeriod(obj, 0); + // Connect signals for all instances + eventMask = EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if(obj.isMetadata()) + eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) + + connectToObjectInstances(obj, eventMask); + } + else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_MANUAL ) + { + // Set update period + setUpdatePeriod(obj, 0); + // Connect signals for all instances + eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if(obj.isMetadata()) + eventMask |= EV_UNPACKED; // we also need to act on remote updates (unpack events) + + connectToObjectInstances(obj, eventMask); + } + else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_NEVER ) + { + // Set update period + setUpdatePeriod(obj, 0); + // Disconnect from object + connectToObjectInstances(obj, 0); + } + } + + /** + * Called when a transaction is successfully completed (uavtalk event) + */ + private void transactionCompleted(UAVObject obj) + { + // Check if there is a pending transaction and the objects match + if ( transPending && transInfo.obj.getObjID() == obj.getObjID() ) + { + // qDebug() << QString("Telemetry: transaction completed for %1").arg(obj->getName()); + // Complete transaction + transTimer.cancel(); + transPending = false; + // Send signal + obj.transactionCompleted(true); + // Process new object updates from queue + processObjectQueue(); + } else + { + // qDebug() << "Error: received a transaction completed when did not expect it."; + } + } + + /** + * Called when a transaction is not completed within the timeout period (timer event) + */ + private void transactionTimeout() + { +// qDebug() << "Telemetry: transaction timeout."; + transTimer.cancel(); + // Proceed only if there is a pending transaction + if ( transPending ) + { + // Check if more retries are pending + if (transInfo.retriesRemaining > 0) + { + --transInfo.retriesRemaining; + processObjectTransaction(); + ++txRetries; + } + else + { + // Terminate transaction + utalk.cancelTransaction(); + transPending = false; + // Send signal + transInfo.obj.transactionCompleted(false); + // Process new object updates from queue + processObjectQueue(); + ++txErrors; + } + } + } + + /** + * Start an object transaction with UAVTalk, all information is stored in transInfo + */ + private void processObjectTransaction() + { + if (transPending) + { + // qDebug() << tr("Process Object transaction for %1").arg(transInfo.obj->getName()); + // Initiate transaction + if (transInfo.objRequest) + { + utalk.sendObjectRequest(transInfo.obj, transInfo.allInstances); + } + else + { + utalk.sendObject(transInfo.obj, transInfo.acked == Acked.TRUE, transInfo.allInstances); + } + // Start timer if a response is expected + if ( transInfo.objRequest || transInfo.acked == Acked.TRUE ) + { + transTimer.scheduleAtFixedRate(transTimerTask, REQ_TIMEOUT_MS, REQ_TIMEOUT_MS); + } + else + { + transTimer.cancel(); + transPending = false; + } + } else + { + // qDebug() << "Error: inside of processObjectTransaction with no transPending"; + } + } + + /** + * Process the event received from an object + */ + private void processObjectUpdates(UAVObject obj, int event, boolean allInstances, boolean priority) + { + // Push event into queue +// qDebug() << "Push event into queue for obj " << QString("%1 event %2").arg(obj->getName()).arg(event); + ObjectQueueInfo objInfo = new ObjectQueueInfo(); + objInfo.obj = obj; + objInfo.event = event; + objInfo.allInstances = allInstances; + if (priority) + { + if ( objPriorityQueue.size() < MAX_QUEUE_SIZE ) + { + objPriorityQueue.add(objInfo); + } + else + { + ++txErrors; + obj.transactionCompleted(false); + //qxtLog->warning(tr("Telemetry: priority event queue is full, event lost (%1)").arg(obj->getName())); + } + } + else + { + if ( objQueue.size() < MAX_QUEUE_SIZE ) + { + objQueue.add(objInfo); + } + else + { + ++txErrors; + obj.transactionCompleted(false); + } + } + + // If there is no transaction in progress then process event + if (!transPending) + { + // qDebug() << "No transaction pending, process object queue..."; + processObjectQueue(); + } else + { + // qDebug() << "Transaction pending, DO NOT process object queue..."; + } + } + + /** + * Process events from the object queue + */ + private void processObjectQueue() + { + // qDebug() << "Process object queue " << tr("- Depth (%1 %2)").arg(objQueue.length()).arg(objPriorityQueue.length()); + + // Don nothing if a transaction is already in progress (should not happen) + if (transPending) + { +// qxtLog->error("Telemetry: Dequeue while a transaction pending!"); + return; + } + + // Get object information from queue (first the priority and then the regular queue) + ObjectQueueInfo objInfo; + if ( !objPriorityQueue.isEmpty() ) + { + objInfo = objPriorityQueue.remove(); + } + else if ( !objQueue.isEmpty() ) + { + objInfo = objQueue.remove(); + } + else + { + return; + } + + // Check if a connection has been established, only process GCSTelemetryStats updates + // (used to establish the connection) + if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 ) + { + objQueue.clear(); + if ( objInfo.obj.getObjID() != objMngr.getObject("GCSTelemetryStats").getObjID() ) + { + objInfo.obj.transactionCompleted(false); + return; + } + } + + // Setup transaction (skip if unpack event) + if ( objInfo.event != EV_UNPACKED ) + { + UAVObject.Metadata metadata = objInfo.obj.getMetadata(); + transInfo.obj = objInfo.obj; + transInfo.allInstances = objInfo.allInstances; + transInfo.retriesRemaining = MAX_RETRIES; + transInfo.acked = metadata.gcsTelemetryAcked; + if ( objInfo.event == EV_UPDATED || objInfo.event == EV_UPDATED_MANUAL ) + { + transInfo.objRequest = false; + } + else if ( objInfo.event == EV_UPDATE_REQ ) + { + transInfo.objRequest = true; + } + // Start transaction + transPending = true; + processObjectTransaction(); + } else + { +// qDebug() << QString("Process object queue: this is an unpack event for %1").arg(objInfo.obj->getName()); + } + + // If this is a metaobject then make necessary telemetry updates + if (objInfo.obj.isMetadata()) + { + UAVMetaObject metaobj = (UAVMetaObject) objInfo.obj; + updateObject( metaobj.getParentObject() ); + } + + // The fact we received an unpacked event does not mean that + // we do not have additional objects still in the queue, + // so we have to reschedule queue processing to make sure they are not + // stuck: + if ( objInfo.event == EV_UNPACKED ) + processObjectQueue(); + + } + + /** + * Check is any objects are pending for periodic updates + * TODO: Clean-up + */ + private synchronized void processPeriodicUpdates() + { + // Stop timer + updateTimer.cancel(); + + // Iterate through each object and update its timer, if zero then transmit object. + // Also calculate smallest delay to next update (will be used for setting timeToNextUpdateMs) + int minDelay = MAX_UPDATE_PERIOD_MS; + ObjectTimeInfo objinfo; + int elapsedMs = 0; + long startTime; + int offset; + ListIterator li = objList.listIterator(); + while(li.hasNext()) + { + objinfo = li.next(); + // If object is configured for periodic updates + if (objinfo.updatePeriodMs > 0) + { + objinfo.timeToNextUpdateMs -= timeToNextUpdateMs; + // Check if time for the next update + if (objinfo.timeToNextUpdateMs <= 0) + { + // Reset timer + offset = (-objinfo.timeToNextUpdateMs) % objinfo.updatePeriodMs; + objinfo.timeToNextUpdateMs = objinfo.updatePeriodMs - offset; + // Send object + startTime = System.currentTimeMillis(); + processObjectUpdates(objinfo.obj, EV_UPDATED_MANUAL, true, false); + elapsedMs = (int) (System.currentTimeMillis() - startTime); + // Update timeToNextUpdateMs with the elapsed delay of sending the object; + timeToNextUpdateMs += elapsedMs; + } + // Update minimum delay + if (objinfo.timeToNextUpdateMs < minDelay) + { + minDelay = objinfo.timeToNextUpdateMs; + } + } + } + + // Check if delay for the next update is too short + if (minDelay < MIN_UPDATE_PERIOD_MS) + { + minDelay = MIN_UPDATE_PERIOD_MS; + } + + // Done + timeToNextUpdateMs = minDelay; + + // Restart timer + //updateTimer->start(timeToNextUpdateMs); + updateTimer.scheduleAtFixedRate(updateTimerTask, timeToNextUpdateMs, timeToNextUpdateMs); + } + + public TelemetryStats getStats() + { + // Get UAVTalk stats + UAVTalk.ComStats utalkStats = utalk.getStats(); + + // Update stats + TelemetryStats stats = new TelemetryStats(); + stats.txBytes = utalkStats.txBytes; + stats.rxBytes = utalkStats.rxBytes; + stats.txObjectBytes = utalkStats.txObjectBytes; + stats.rxObjectBytes = utalkStats.rxObjectBytes; + stats.rxObjects = utalkStats.rxObjects; + stats.txObjects = utalkStats.txObjects; + stats.txErrors = utalkStats.txErrors + txErrors; + stats.rxErrors = utalkStats.rxErrors; + stats.txRetries = txRetries; + + // Done + return stats; + } + + public synchronized void resetStats() + { + utalk.resetStats(); + txErrors = 0; + txRetries = 0; + } + + private synchronized void objectUpdatedAuto(UAVObject obj) + { + processObjectUpdates(obj, EV_UPDATED, false, true); + } + + private synchronized void objectUpdatedManual(UAVObject obj) + { + processObjectUpdates(obj, EV_UPDATED_MANUAL, false, true); + } + + private synchronized void objectUnpacked(UAVObject obj) + { + processObjectUpdates(obj, EV_UNPACKED, false, true); + } + + private synchronized void updateRequested(UAVObject obj) + { + processObjectUpdates(obj, EV_UPDATE_REQ, false, true); + } + + private void newObject(UAVObject obj) + { + registerObject(obj); + } + + private synchronized void newInstance(UAVObject obj) + { + registerObject(obj); + } + + /** + * Private variables + */ + private TelemetryStats stats; + private UAVObjectManager objMngr; + private UAVTalk utalk; + private UAVObject gcsStatsObj; + private List objList; + private Queue objQueue = new LinkedList(); + private Queue objPriorityQueue = new LinkedList(); + private ObjectTransactionInfo transInfo; + private boolean transPending; + + private Timer updateTimer; + private TimerTask updateTimerTask; + private Timer transTimer; + private TimerTask transTimerTask; + + private int timeToNextUpdateMs; + private int txErrors; + private int txRetries; + + /** + * Private constants + */ + private static final int REQ_TIMEOUT_MS = 250; + private static final int MAX_RETRIES = 2; + private static final int MAX_UPDATE_PERIOD_MS = 1000; + private static final int MIN_UPDATE_PERIOD_MS = 1; + private static final int MAX_QUEUE_SIZE = 20; + + + } diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 40fc220cc..39d332457 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -123,7 +123,7 @@ public class TelemetryMonitor { // Connect to object //connect(obj, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(transactionCompleted(UAVObject*,bool))); // Request update - obj.requestUpdate(); + tel.requestUpdate(obj); objPending = obj; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index adfece03e..9e4f69a39 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -8,7 +8,7 @@ import java.util.Observer; import java.util.Observable; public abstract class UAVObject { - + public class CallbackListener extends Observable { private UAVObject parent; @@ -20,6 +20,31 @@ public abstract class UAVObject { setChanged(); notifyObservers(parent); } + public void event (Object data) { + setChanged(); + notifyObservers(data); + } + } + + public class TransactionResult { + public UAVObject obj; + public boolean success; + public TransactionResult(UAVObject obj, boolean success) { + this.obj = obj; + this.success = success; + } + } + + private CallbackListener transactionCompletedListeners = new CallbackListener(this); + public void addTransactionCompleted(Observer o) { + synchronized(transactionCompletedListeners) { + transactionCompletedListeners.addObserver(o); + } + } + void transactionCompleted(boolean status) { + synchronized(transactionCompletedListeners) { + transactionCompletedListeners.event(new TransactionResult(this,status)); + } } private CallbackListener updatedListeners = new CallbackListener(this); @@ -47,6 +72,30 @@ public abstract class UAVObject { } } + private CallbackListener updatedAutoListeners = new CallbackListener(this); + public void addUpdatedAutoObserver(Observer o) { + synchronized(updatedAutoListeners) { + updatedAutoListeners.addObserver(o); + } + } + void updatedAuto() { + synchronized(updatedAutoListeners) { + updatedAutoListeners.event(); + } + } + + private CallbackListener updatedManualListeners = new CallbackListener(this); + public void addUpdatedManualObserver(Observer o) { + synchronized(updatedManualListeners) { + updatedManualListeners.addObserver(o); + } + } + void updatedManual() { + synchronized(updatedManualListeners) { + updatedManualListeners.event(); + } + } + public abstract boolean isMetadata(); /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 63f535eac..3ec588879 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -102,7 +102,6 @@ public class UAVObjectManager { newInstance.event(newObj); } obj.initialize(mobj); - //emit new instance signal instList.add(obj); newInstance.event(obj); @@ -155,7 +154,7 @@ public class UAVObjectManager { List ls = new ArrayList(); ls.add(obj); objects.add(ls); - //emit newObject(obj); + newObject.event(obj); } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 7ea9c7c60..847b7c425 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -7,8 +7,9 @@ import java.io.InputStream; import java.io.OutputStream; import java.nio.ByteBuffer; import java.nio.ByteOrder; +import java.util.Observable; -public class UAVTalk { +public class UAVTalk extends Observable{ private Thread inputProcessingThread = null; /** @@ -632,8 +633,8 @@ public class UAVTalk { if (respObj != null && respObj.getObjID() == obj.getObjID() && (respObj.getInstID() == obj.getInstID() || respAllInstances)) { respObj = null; - // TODO: Signals -// emit transactionCompleted(obj); + setChanged(); + notifyObservers(obj); } } From b10c3f623d5312948ac306bc3f5b2de8b24a3a45 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 02:39:33 -0600 Subject: [PATCH 217/543] Changes to TelemetryMonitor, ready for testing --- .../src/org/openpilot/uavtalk/Telemetry.java | 2 +- .../openpilot/uavtalk/TelemetryMonitor.java | 54 +++++++++++-------- 2 files changed, 32 insertions(+), 24 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 79e821fe3..4bed72fea 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -585,7 +585,7 @@ public class Telemetry { processObjectUpdates(obj, EV_UNPACKED, false, true); } - private synchronized void updateRequested(UAVObject obj) + public synchronized void updateRequested(UAVObject obj) { processObjectUpdates(obj, EV_UPDATE_REQ, false, true); } diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 39d332457..dabbf1d4b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -28,6 +28,7 @@ public class TelemetryMonitor { private UAVObject flightStatsObj; private Timer periodicTask; private int currentPeriod; + private long lastUpdateTime; private List queue; public TelemetryMonitor(UAVObjectManager objMngr, Telemetry tel) @@ -121,9 +122,15 @@ public class TelemetryMonitor { Log.d(TAG, "Retrieving object: " + obj.getName()) ; // Connect to object - //connect(obj, SIGNAL(transactionCompleted(UAVObject*,bool)), this, SLOT(transactionCompleted(UAVObject*,bool))); + obj.addTransactionCompleted(new Observer() { + public void update(Observable observable, Object data) { + UAVObject.TransactionResult result = (UAVObject.TransactionResult) data; + transactionCompleted(result.obj, result.success); + } + }); + // Request update - tel.requestUpdate(obj); + tel.updateRequested(obj); objPending = obj; } @@ -184,9 +191,10 @@ public class TelemetryMonitor { boolean connectionTimeout; if ( telStats.rxObjects > 0 ) { - //connectionTimer.start(); + lastUpdateTime = System.currentTimeMillis(); + } - if ( connectionTimer.elapsed() > CONNECTION_TIMEOUT_MS ) + if ( (System.currentTimeMillis() - lastUpdateTime) > CONNECTION_TIMEOUT_MS ) { connectionTimeout = true; } @@ -196,53 +204,53 @@ public class TelemetryMonitor { } // Update connection state - int oldStatus = gcsStats.Status; - if ( gcsStats.Status == GCSTelemetryStats::STATUS_DISCONNECTED ) + UAVObjectField statusField = gcsStatsObj.getField("Connection"); + String oldStatus = (String) statusField.getValue(); + if ( oldStatus.compareTo("Disconnected") == 0 ) { // Request connection - gcsStats.Status = GCSTelemetryStats::STATUS_HANDSHAKEREQ; + statusField.setValue("HandshakeReq"); } - else if ( gcsStats.Status == GCSTelemetryStats::STATUS_HANDSHAKEREQ ) + else if ( oldStatus.compareTo("HandshakeReq") == 0 ) { // Check for connection acknowledge - if ( flightStats.Status == FlightTelemetryStats::STATUS_HANDSHAKEACK ) + if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("HandshakeAck") == 0 ) { - gcsStats.Status = GCSTelemetryStats::STATUS_CONNECTED; + statusField.setValue("Connected"); } } - else if ( gcsStats.Status == GCSTelemetryStats::STATUS_CONNECTED ) + else if ( oldStatus.compareTo("Connected") == 0 ) { // Check if the connection is still active and the the autopilot is still connected - if (flightStats.Status == FlightTelemetryStats::STATUS_DISCONNECTED || connectionTimeout) + if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") == 0 || connectionTimeout) { - gcsStats.Status = GCSTelemetryStats::STATUS_DISCONNECTED; + statusField.setValue("Disconnected"); } } - // Set data - gcsStatsObj->setData(gcsStats); - // Force telemetry update if not yet connected - if ( gcsStats.Status != GCSTelemetryStats::STATUS_CONNECTED || - flightStats.Status != FlightTelemetryStats::STATUS_CONNECTED ) + boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); + boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; + boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; + if ( gcsStatusChanged || + ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") != 0 ) { - gcsStatsObj->updated(); + gcsStatsObj.updated(); } // Act on new connections or disconnections - if (gcsStats.Status == GCSTelemetryStats::STATUS_CONNECTED && gcsStats.Status != oldStatus) + if (gcsConnected && gcsStatusChanged) { setPeriod(STATS_UPDATE_PERIOD_MS); - statsTimer->setInterval(STATS_UPDATE_PERIOD_MS); Log.d(TAG,"Connection with the autopilot established"); startRetrievingObjects(); } - if (gcsStats.Status == GCSTelemetryStats::STATUS_DISCONNECTED && gcsStats.Status != oldStatus) + if (gcsDisconnected && gcsStatusChanged) { setPeriod(STATS_CONNECT_PERIOD_MS); Log.d(TAG,"Connection with the autopilot lost"); Log.d(TAG,"Trying to connect to the autopilot"); - emit disconnected(); + //emit disconnected(); } } From f80424875e58106f9e54a6d17ecdf96e7e559fad Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 12:27:27 -0600 Subject: [PATCH 218/543] Fixed bug in object signals that stopped updates sending. Various tweaks. --- .../src/org/openpilot/uavtalk/Telemetry.java | 33 ++++++++++------- .../openpilot/uavtalk/TelemetryMonitor.java | 35 +++++++++++++++---- .../org/openpilot/uavtalk/UAVDataObject.java | 2 +- .../src/org/openpilot/uavtalk/UAVObject.java | 8 +++-- .../org/openpilot/uavtalk/UAVObjectField.java | 4 +-- .../src/org/openpilot/uavtalk/UAVTalk.java | 15 +++++--- 6 files changed, 68 insertions(+), 29 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 4bed72fea..d2f82459b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -1,5 +1,6 @@ package org.openpilot.uavtalk; +import java.util.ArrayList; import java.util.LinkedList; import java.util.List; import java.util.ListIterator; @@ -91,6 +92,15 @@ public class Telemetry { // Setup transaction timer transPending = false; + // Setup and start the periodic timer + timeToNextUpdateMs = 0; + updateTimerSetPeriod(1000); + // Setup and start the stats timer + txErrors = 0; + txRetries = 0; + } + + synchronized void transTimerSetPeriod(int periodMs) { transTimer = new Timer(); transTimerTask = new TimerTask() { @Override @@ -98,9 +108,10 @@ public class Telemetry { transactionTimeout(); } }; - // Setup and start the periodic timer - timeToNextUpdateMs = 0; - + transTimer.schedule(transTimerTask, periodMs, periodMs); + } + + synchronized void updateTimerSetPeriod(int periodMs) { updateTimer = new Timer(); updateTimerTask = new TimerTask() { @Override @@ -108,10 +119,8 @@ public class Telemetry { processPeriodicUpdates(); } }; - updateTimer.scheduleAtFixedRate(updateTimerTask, 1000, 1000); - // Setup and start the stats timer - txErrors = 0; - txRetries = 0; + updateTimer.schedule(updateTimerTask, periodMs, periodMs); + } /** @@ -341,7 +350,7 @@ public class Telemetry { // Start timer if a response is expected if ( transInfo.objRequest || transInfo.acked == Acked.TRUE ) { - transTimer.scheduleAtFixedRate(transTimerTask, REQ_TIMEOUT_MS, REQ_TIMEOUT_MS); + transTimerSetPeriod(REQ_TIMEOUT_MS); } else { @@ -433,6 +442,7 @@ public class Telemetry { // Check if a connection has been established, only process GCSTelemetryStats updates // (used to establish the connection) + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 ) { objQueue.clear(); @@ -538,8 +548,7 @@ public class Telemetry { timeToNextUpdateMs = minDelay; // Restart timer - //updateTimer->start(timeToNextUpdateMs); - updateTimer.scheduleAtFixedRate(updateTimerTask, timeToNextUpdateMs, timeToNextUpdateMs); + updateTimerSetPeriod(timeToNextUpdateMs); } public TelemetryStats getStats() @@ -607,10 +616,10 @@ public class Telemetry { private UAVObjectManager objMngr; private UAVTalk utalk; private UAVObject gcsStatsObj; - private List objList; + private List objList = new ArrayList(); private Queue objQueue = new LinkedList(); private Queue objPriorityQueue = new LinkedList(); - private ObjectTransactionInfo transInfo; + private ObjectTransactionInfo transInfo = new ObjectTransactionInfo(); private boolean transPending; private Timer updateTimer; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index dabbf1d4b..bc0bfd6eb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -92,7 +92,7 @@ public class TelemetryMonitor { } } // Start retrieving - Log.d(TAG,"Starting to retrieve meta and settings objects from the autopilot (%1 objects)" + queue.size()) ; + System.out.println(TAG + "Starting to retrieve meta and settings objects from the autopilot (" + queue.size() + " objects)"); retrieveNextObject(); } @@ -120,7 +120,7 @@ public class TelemetryMonitor { // Get next object from the queue UAVObject obj = queue.remove(0); - Log.d(TAG, "Retrieving object: " + obj.getName()) ; +// Log.d(TAG, "Retrieving object: " + obj.getName()) ; // Connect to object obj.addTransactionCompleted(new Observer() { public void update(Observable observable, Object data) { @@ -161,6 +161,10 @@ public class TelemetryMonitor { public synchronized void flightStatsUpdated(UAVObject obj) { // Force update if not yet connected + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); + flightStatsObj = objMngr.getObject("FlightTelemetryStats"); + + System.out.println(flightStatsObj.toString()); if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) { @@ -204,8 +208,17 @@ public class TelemetryMonitor { } // Update connection state - UAVObjectField statusField = gcsStatsObj.getField("Connection"); + gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); + flightStatsObj = objMngr.getObject("FlightTelemetryStats"); + if(gcsStatsObj == null) { + System.out.println("No GCS stats yet"); + return; + } + UAVObjectField statusField = gcsStatsObj.getField("Status"); String oldStatus = (String) statusField.getValue(); + + System.out.println("GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); + if ( oldStatus.compareTo("Disconnected") == 0 ) { // Request connection @@ -217,6 +230,7 @@ public class TelemetryMonitor { if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("HandshakeAck") == 0 ) { statusField.setValue("Connected"); + System.out.println("Connected" + statusField.toString()); } } else if ( oldStatus.compareTo("Connected") == 0 ) @@ -230,11 +244,18 @@ public class TelemetryMonitor { // Force telemetry update if not yet connected boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); + + if(gcsStatusChanged) + System.out.println("GCS Status changed"); boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; + + if(gcsConnected) + System.out.println("Detected here"); if ( gcsStatusChanged || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") != 0 ) { + System.out.println("Sending gcs status\n\n\n"); gcsStatsObj.updated(); } @@ -242,14 +263,15 @@ public class TelemetryMonitor { if (gcsConnected && gcsStatusChanged) { setPeriod(STATS_UPDATE_PERIOD_MS); - Log.d(TAG,"Connection with the autopilot established"); + System.out.println(TAG + " Connection with the autopilot established"); + //Log.d(TAG,"Connection with the autopilot established"); startRetrievingObjects(); } if (gcsDisconnected && gcsStatusChanged) { setPeriod(STATS_CONNECT_PERIOD_MS); - Log.d(TAG,"Connection with the autopilot lost"); - Log.d(TAG,"Trying to connect to the autopilot"); + System.out.println(TAG + " Connection with the autopilot lost"); + //Log.d(TAG,"Trying to connect to the autopilot"); //emit disconnected(); } } @@ -260,6 +282,7 @@ public class TelemetryMonitor { periodicTask.cancel(); currentPeriod = ms; + periodicTask = new Timer(); periodicTask.scheduleAtFixedRate(new TimerTask() { @Override public void run() { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java index 5694cc9d8..0acc02226 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java @@ -24,7 +24,7 @@ public abstract class UAVDataObject extends UAVObject { super.initialize(instID); } - public boolean isMetadata() { return true; }; + public boolean isMetadata() { return false; }; /** * Assign a metaobject */ diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 9e4f69a39..fac67cabc 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -53,11 +53,14 @@ public abstract class UAVObject { updatedListeners.addObserver(o); } } - void updated() { + void updated(boolean manually) { synchronized(updatedListeners) { updatedListeners.event(); } + if(manually) + updatedManual(); } + void updated() { updated(true); }; private CallbackListener unpackedListeners = new CallbackListener(this); public void addUnpackedObserver(Observer o) { @@ -67,7 +70,6 @@ public abstract class UAVObject { } void unpacked() { synchronized(unpackedListeners) { - System.out.println("Unpacked!: " + unpackedListeners.countObservers() + " " + getName()); unpackedListeners.event(); } } @@ -387,7 +389,7 @@ public abstract class UAVObject { // Trigger all the listeners for the unpack event unpacked(); - updated(); + updated(false); return numBytes; } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 2fd7f7846..8d792bb39 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -131,7 +131,7 @@ public class UAVObjectField { case UINT32: // TODO: Deal properly with unsigned for (int index = 0; index < numElements; ++index) { - Integer val = (Integer) getValue(index); + Integer val = (int) ( ((Long) getValue(index)).longValue() & 0xffffffffL); dataOut.putInt(val); } break; @@ -364,7 +364,7 @@ public class UAVObjectField { public double getDouble() { return getDouble(0); }; public double getDouble(int index) { - return Double.valueOf((Double) getValue(index)); + return ((Number) getValue(index)).doubleValue(); } public void setDouble(double value) { setDouble(value, 0); }; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 847b7c425..8576be78c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -200,9 +200,9 @@ public class UAVTalk extends Observable{ * \param[in] allInstances If set true then all instances will be updated * \return Success (true), Failure (false) */ - public boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) + public synchronized boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) { - //QMutexLocker locker(mutex); + System.out.println("Sending obj: " + obj.toString()); if (acked) { return objectTransaction(obj, TYPE_OBJ_ACK, allInstances); @@ -216,9 +216,8 @@ public class UAVTalk extends Observable{ /** * Cancel a pending transaction */ - public void cancelTransaction() + public synchronized void cancelTransaction() { - //QMutexLocker locker(mutex); respObj = null; } @@ -250,6 +249,7 @@ public class UAVTalk extends Observable{ } else if (type == TYPE_OBJ) { + System.out.println("Transmitting object: " + obj.toString()); return transmitObject(obj, TYPE_OBJ, allInstances); } else @@ -763,7 +763,12 @@ public class UAVTalk extends Observable{ bbuf.put((byte) (updateCRC(0, bbuf.array()) & 0xff)); try { - outStream.write(bbuf.array()); + int packlen = bbuf.position(); + bbuf.position(0); + byte [] dst = new byte[packlen]; + bbuf.get(dst,0,packlen); + System.out.println("Outputting: " + dst.length); + outStream.write(dst); } catch (IOException e) { // TODO Auto-generated catch block e.printStackTrace(); From abc07fd7484d58a4abf79c370493962305a183fb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 12:27:59 -0600 Subject: [PATCH 219/543] Unit test for telemetry --- .../uavtalk/TelemetryMonitorTest.java | 64 +++++++++++++++++++ 1 file changed, 64 insertions(+) create mode 100644 androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java diff --git a/androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java b/androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java new file mode 100644 index 000000000..1fc02d145 --- /dev/null +++ b/androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java @@ -0,0 +1,64 @@ +package org.openpilot.uavtalk; + +import static org.junit.Assert.*; + +import java.io.IOException; +import java.io.InputStream; +import java.io.InputStreamReader; +import java.io.OutputStream; +import java.net.DatagramSocket; +import java.net.InetAddress; +import java.net.Socket; +import java.nio.ByteBuffer; +import java.util.Observable; +import java.util.Observer; + +import org.junit.BeforeClass; +import org.junit.Test; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; +import org.openpilot.uavtalk.UAVTalk; + + +public class TelemetryMonitorTest { + + static UAVObjectManager objMngr; + static UAVTalk talk; + static final String IP_ADDRDESS = new String("127.0.0.1"); + static final int PORT_NUM = 7777; + static Socket connection = null; + boolean succeed = false; + + @Test + public void testTelemetry() throws Exception { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + talk = null; + try{ + InetAddress ip = InetAddress.getByName(IP_ADDRDESS); + connection = new Socket(ip, PORT_NUM); + } catch (Exception e) { + e.printStackTrace(); + fail("Couldn't connect to test platform"); + } + + try { + talk = new UAVTalk(connection.getInputStream(), connection.getOutputStream(), objMngr); + } catch (IOException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + fail("Couldn't construct UAVTalk object"); + } + + Thread inputStream = talk.getInputProcessThread(); + inputStream.start(); + + Telemetry tel = new Telemetry(talk, objMngr); + TelemetryMonitor mon = new TelemetryMonitor(objMngr,tel); + + Thread.sleep(10000); + + System.out.println("Done"); + } + + +} From 29fd09b204c5d95a95da2c3293327c75f7b0275e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 13:44:40 -0600 Subject: [PATCH 220/543] Little updates --- .../src/org/openpilot/uavtalk/UAVTalk.java | 16 +++--- .../tests/org/openpilot/uavtalk/TalkTest.java | 56 ++++++++++++++----- 2 files changed, 51 insertions(+), 21 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 8576be78c..92b5585de 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -202,7 +202,6 @@ public class UAVTalk extends Observable{ */ public synchronized boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) { - System.out.println("Sending obj: " + obj.toString()); if (acked) { return objectTransaction(obj, TYPE_OBJ_ACK, allInstances); @@ -249,7 +248,6 @@ public class UAVTalk extends Observable{ } else if (type == TYPE_OBJ) { - System.out.println("Transmitting object: " + obj.toString()); return transmitObject(obj, TYPE_OBJ, allInstances); } else @@ -263,7 +261,7 @@ public class UAVTalk extends Observable{ * \param[in] rxbyte Received byte * \return Success (true), Failure (false) */ - public boolean processInputByte(int rxbyte) + public synchronized boolean processInputByte(int rxbyte) { assert(objMngr != null); @@ -448,12 +446,10 @@ public class UAVTalk extends Observable{ break; } - //mutex->lock(); rxBuffer.position(0); receiveObject(rxType, rxObjId, rxInstId, rxBuffer); stats.rxObjectBytes += rxLength; stats.rxObjects++; - //mutex->unlock(); rxState = RxStateType.STATE_SYNC; break; @@ -484,13 +480,13 @@ public class UAVTalk extends Observable{ boolean error = false; boolean allInstances = (instId == ALL_INSTANCES? true : false); - System.out.println("Received object: " + objId + " " + objMngr.getObject(objId).getName()); // Process message type switch (type) { case TYPE_OBJ: // All instances, not allowed for OBJ messages if (!allInstances) { + System.out.println("Received object: " + objId + " " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Check if an ack is pending @@ -512,6 +508,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for OBJ_ACK messages if (!allInstances) { + System.out.println("Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK @@ -531,6 +528,7 @@ public class UAVTalk extends Observable{ break; case TYPE_OBJ_REQ: // Get object, if all instances are requested get instance 0 of the object + System.out.println("Received object request: " + objId + " " + objMngr.getObject(objId).getName()); if (allInstances) { obj = objMngr.getObject(objId); @@ -553,6 +551,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for ACK messages if (!allInstances) { + System.out.println("Received ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending @@ -578,7 +577,7 @@ public class UAVTalk extends Observable{ * If the object instance could not be found in the list, then a * new one is created. */ - public UAVObject updateObject(int objId, int instId, ByteBuffer data) + public synchronized UAVObject updateObject(int objId, int instId, ByteBuffer data) { assert(objMngr != null); @@ -613,13 +612,14 @@ public class UAVTalk extends Observable{ // TODO Auto-generated catch block e.printStackTrace(); } + System.out.println("Unpacking new object"); instobj.unpack(data); return instobj; } else { // Unpack data into object instance - // System.out.println("Unpacking: " + data.position() + " / " + data.capacity() ); + System.out.println("Unpacking existing object: " + data.position() + " / " + data.capacity() ); obj.unpack(data); return obj; } diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java index 252927122..044ddfd06 100644 --- a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java +++ b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java @@ -1,10 +1,13 @@ package org.openpilot.uavtalk; import static org.junit.Assert.*; +import java.io.ByteArrayInputStream; +import java.io.ByteArrayOutputStream; import java.io.IOException; import java.io.InputStream; import java.io.InputStreamReader; import java.io.OutputStream; +import java.io.OutputStreamWriter; import java.net.DatagramSocket; import java.net.InetAddress; import java.net.Socket; @@ -31,7 +34,7 @@ public class TalkTest { UAVObjectsInitialize.register(objMngr); } - @Test + //@Test public void testGetFlightStatus() { Socket connection = null; UAVTalk talk = null; @@ -78,22 +81,49 @@ public class TalkTest { @Test public void testSendObjectRequest() { - fail("Not yet implemented"); + ByteArrayInputStream is = new ByteArrayInputStream(new byte[0], 0, 0); + ByteArrayOutputStream os = new ByteArrayOutputStream(100); + + UAVTalk talk = new UAVTalk(is,os,objMngr); + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + obj.getField("Status").setValue("Connected"); + + talk.sendObject(obj, false, false); + + System.out.println("Size: " + os.size()); + byte [] array = os.toByteArray(); + for(int i = 0; i < array.length; i++) { + System.out.print("0x" + Integer.toHexString((int) array[i] & 0xff)); + if(i != array.length-1) + System.out.print(", "); + } + System.out.print("\n"); } - - @Test - public void testSendObject() { - fail("Not yet implemented"); - } - + @Test public void testReceiveObject() { - fail("Not yet implemented"); + ByteArrayInputStream is = new ByteArrayInputStream(new byte[0], 0, 0); + ByteArrayOutputStream os = new ByteArrayOutputStream(100); + + // Send object to create the test packet (should hard code in test string) + UAVTalk talk = new UAVTalk(is,os,objMngr); + UAVObject obj = objMngr.getObject("FlightTelemetryStats"); + obj.getField("Status").setValue("Connected"); + talk.sendObject(obj, false, false); + + obj.getField("Status").setValue("Disconnected"); + + // Test receiving from that stream + is = new ByteArrayInputStream(os.toByteArray(), 0, os.size()); + talk = new UAVTalk(is,os,objMngr); + Thread inputStream = talk.getInputProcessThread(); + inputStream.start(); + + System.out.println("Should be FlightTelemetry Stats:"); + System.out.println(objMngr.getObject("FlightTelemetryStats").toString()); + + fail("Not working yet"); } - @Test - public void testUpdateObject() { - fail("Not yet implemented"); - } } From 1ea90c415879a2ea123af97d0d14b7137aa5a243 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 14:36:37 -0600 Subject: [PATCH 221/543] Fix the CRC calculation for java sending --- .../src/org/openpilot/uavtalk/UAVTalk.java | 13 ++++--- .../tests/org/openpilot/uavtalk/TalkTest.java | 34 ++++++++++++------- 2 files changed, 31 insertions(+), 16 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 92b5585de..d656aa707 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -175,7 +175,12 @@ public class UAVTalk extends Observable{ e.printStackTrace(); break; } - //System.out.println("Received byte " + val + " in state + " + rxState); + if(val == -1) { + System.out.println("End of stream, terminating processInputStream thread"); + break; + } + + System.out.println("Received byte " + val + " in state + " + rxState); processInputByte(val); } } @@ -760,7 +765,7 @@ public class UAVTalk extends Observable{ } // Calculate checksum - bbuf.put((byte) (updateCRC(0, bbuf.array()) & 0xff)); + bbuf.put((byte) (updateCRC(0, bbuf.array(), bbuf.position()) & 0xff)); try { int packlen = bbuf.position(); @@ -818,9 +823,9 @@ public class UAVTalk extends Observable{ { return crc_table[crc ^ (data & 0xff)]; } - int updateCRC(int crc, byte [] data) + int updateCRC(int crc, byte [] data, int length) { - for (int i = 0; i < data.length; i++) + for (int i = 0; i < length; i++) crc = updateCRC(crc, (int) data[i]); return crc; } diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java index 044ddfd06..91f3aa198 100644 --- a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java +++ b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java @@ -28,6 +28,16 @@ public class TalkTest { static final int PORT_NUM = 7777; boolean succeed = false; + byte[] flightStatsConnected = + {0x3c,0x20,0x1d,0x00, + (byte) 0x5e,(byte) 0x26,(byte) 0x0c,(byte) 0x66, + 0x03,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00, + 0x00,0x00,0x00,0x00, + 0x00,(byte) 0xAE}; + @BeforeClass public static void setUpBeforeClass() throws Exception { objMngr = new UAVObjectManager(); @@ -89,40 +99,40 @@ public class TalkTest { obj.getField("Status").setValue("Connected"); talk.sendObject(obj, false, false); - + System.out.println("Size: " + os.size()); byte [] array = os.toByteArray(); for(int i = 0; i < array.length; i++) { System.out.print("0x" + Integer.toHexString((int) array[i] & 0xff)); + System.out.print("/0x" + Integer.toHexString((int) flightStatsConnected[i] & 0xff)); if(i != array.length-1) - System.out.print(", "); + System.out.print("\n"); } System.out.print("\n"); + for(int i = 0; i < array.length; i++) + assertEquals(os.toByteArray()[i], flightStatsConnected[i]); } @Test - public void testReceiveObject() { - ByteArrayInputStream is = new ByteArrayInputStream(new byte[0], 0, 0); + public void testReceiveObject() throws InterruptedException { + ByteArrayInputStream is = new ByteArrayInputStream(flightStatsConnected, 0, flightStatsConnected.length); ByteArrayOutputStream os = new ByteArrayOutputStream(100); - // Send object to create the test packet (should hard code in test string) - UAVTalk talk = new UAVTalk(is,os,objMngr); + // Make the Status wrong initially UAVObject obj = objMngr.getObject("FlightTelemetryStats"); - obj.getField("Status").setValue("Connected"); - talk.sendObject(obj, false, false); - obj.getField("Status").setValue("Disconnected"); // Test receiving from that stream - is = new ByteArrayInputStream(os.toByteArray(), 0, os.size()); - talk = new UAVTalk(is,os,objMngr); + UAVTalk talk = new UAVTalk(is,os,objMngr); Thread inputStream = talk.getInputProcessThread(); inputStream.start(); + Thread.sleep(1000); + System.out.println("Should be FlightTelemetry Stats:"); System.out.println(objMngr.getObject("FlightTelemetryStats").toString()); - fail("Not working yet"); + assertEquals(obj.getField("Status").getValue(), new String("Connected")); } From 20a4021bd32c4dc8f287a2624678ac931f752423 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 Mar 2011 21:36:09 -0600 Subject: [PATCH 222/543] Fixed some timer issues. Got connection with this. --- .../src/org/openpilot/uavtalk/Telemetry.java | 9 ++++++++- .../org/openpilot/uavtalk/TelemetryMonitor.java | 3 --- .../src/org/openpilot/uavtalk/UAVTalk.java | 16 +++++++--------- 3 files changed, 15 insertions(+), 13 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index d2f82459b..7f04e344b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -101,7 +101,14 @@ public class Telemetry { } synchronized void transTimerSetPeriod(int periodMs) { - transTimer = new Timer(); + if(transTimerTask != null) + transTimerTask.cancel(); + + if(transTimer != null) + transTimer.purge(); + + transTimer = new Timer(); + transTimerTask = new TimerTask() { @Override public void run() { diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index bc0bfd6eb..eb406923d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -164,7 +164,6 @@ public class TelemetryMonitor { gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); flightStatsObj = objMngr.getObject("FlightTelemetryStats"); - System.out.println(flightStatsObj.toString()); if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) { @@ -250,8 +249,6 @@ public class TelemetryMonitor { boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; - if(gcsConnected) - System.out.println("Detected here"); if ( gcsStatusChanged || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") != 0 ) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index d656aa707..825f9d9fe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -180,7 +180,7 @@ public class UAVTalk extends Observable{ break; } - System.out.println("Received byte " + val + " in state + " + rxState); + //System.out.println("Received byte " + val + " in state + " + rxState); processInputByte(val); } } @@ -423,7 +423,6 @@ public class UAVTalk extends Observable{ // Update CRC rxCS = updateCRC(rxCS, rxbyte); - //System.out.println(rxCount + "/" + rxLength); rxBuffer.put(rxCount++, (byte) (rxbyte & 0xff)); if (rxCount < rxLength) break; @@ -491,7 +490,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for OBJ messages if (!allInstances) { - System.out.println("Received object: " + objId + " " + objMngr.getObject(objId).getName()); + System.out.println("Received object: " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Check if an ack is pending @@ -513,7 +512,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for OBJ_ACK messages if (!allInstances) { - System.out.println("Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); +// System.out.println("Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK @@ -533,7 +532,7 @@ public class UAVTalk extends Observable{ break; case TYPE_OBJ_REQ: // Get object, if all instances are requested get instance 0 of the object - System.out.println("Received object request: " + objId + " " + objMngr.getObject(objId).getName()); +// System.out.println("Received object request: " + objId + " " + objMngr.getObject(objId).getName()); if (allInstances) { obj = objMngr.getObject(objId); @@ -556,7 +555,7 @@ public class UAVTalk extends Observable{ // All instances, not allowed for ACK messages if (!allInstances) { - System.out.println("Received ack: " + objId + " " + objMngr.getObject(objId).getName()); +// System.out.println("Received ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending @@ -617,14 +616,14 @@ public class UAVTalk extends Observable{ // TODO Auto-generated catch block e.printStackTrace(); } - System.out.println("Unpacking new object"); +// System.out.println("Unpacking new object"); instobj.unpack(data); return instobj; } else { // Unpack data into object instance - System.out.println("Unpacking existing object: " + data.position() + " / " + data.capacity() ); +// System.out.println("Unpacking existing object: " + data.position() + " / " + data.capacity() ); obj.unpack(data); return obj; } @@ -772,7 +771,6 @@ public class UAVTalk extends Observable{ bbuf.position(0); byte [] dst = new byte[packlen]; bbuf.get(dst,0,packlen); - System.out.println("Outputting: " + dst.length); outStream.write(dst); } catch (IOException e) { // TODO Auto-generated catch block From 34dfaf0023c41729ddfe2779eaa965e6b969763d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 13 Mar 2011 21:01:11 -0500 Subject: [PATCH 223/543] Works on Nook, but recursive loop too deep in registering objects --- androidgcs/AndroidManifest.xml | 12 +- androidgcs/default.properties | 2 +- androidgcs/res/layout/main.xml | 1 - androidgcs/res/values/strings.xml | 1 - .../openpilot/androidgcs/ObjectBrowser.java | 129 ++++++++++++++++++ .../src/org/openpilot/uavtalk/Telemetry.java | 47 ++++--- .../openpilot/uavtalk/TelemetryMonitor.java | 15 +- .../src/org/openpilot/uavtalk/UAVObject.java | 12 +- 8 files changed, 186 insertions(+), 33 deletions(-) create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 7a96a6600..8b3a9e4b3 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -5,8 +5,18 @@ android:versionName="1.0"> - + + + + + + + + + + \ No newline at end of file diff --git a/androidgcs/default.properties b/androidgcs/default.properties index 46769a720..66db0d159 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=android-7 +target=android-10 diff --git a/androidgcs/res/layout/main.xml b/androidgcs/res/layout/main.xml index 3a5f117d3..7e4a852bf 100644 --- a/androidgcs/res/layout/main.xml +++ b/androidgcs/res/layout/main.xml @@ -7,6 +7,5 @@ diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 0d9f93bc2..52fa56534 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,5 +1,4 @@ - Hello World! OpenPilot GCS diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java new file mode 100644 index 000000000..3c6231258 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -0,0 +1,129 @@ +package org.openpilot.androidgcs; + +import java.io.IOException; +import java.util.Set; +import java.util.UUID; + +import android.app.Activity; +import android.bluetooth.BluetoothAdapter; +import android.bluetooth.BluetoothDevice; +import android.bluetooth.BluetoothSocket; +import android.content.Intent; +import android.os.Bundle; +import android.util.Log; + +import org.openpilot.androidgcs.*; +import org.openpilot.uavtalk.Telemetry; +import org.openpilot.uavtalk.TelemetryMonitor; +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVTalk; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; + +public class ObjectBrowser extends Activity { + + private final String TAG = "ObjectBrower"; + private final String DEVICE_NAME = "RN42-222D"; + private final int REQUEST_ENABLE_BT = 0; + private UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); + BluetoothAdapter mBluetoothAdapter; + UAVObjectManager objMngr; + UAVTalk uavTalk; + + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.main); + + Log.d(TAG, "Launching Object Browser"); + + mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); + if (mBluetoothAdapter == null) { + // Device does not support Bluetooth + Log.d(TAG, "Device does not support Bluetooth"); + return; + } + + if (!mBluetoothAdapter.isEnabled()) { + Intent enableBtIntent = new Intent(BluetoothAdapter.ACTION_REQUEST_ENABLE); + startActivityForResult(enableBtIntent, REQUEST_ENABLE_BT); + } else { + queryDevices(); + } + } + + @Override + public void onActivityResult(int requestCode, int resultCode, Intent data) { + if(requestCode == REQUEST_ENABLE_BT && resultCode == RESULT_OK) { + Log.d(TAG, "Bluetooth started succesfully"); + queryDevices(); + } + if(requestCode == REQUEST_ENABLE_BT && resultCode != RESULT_OK) + Log.d(TAG, "Bluetooth could not be started"); + + } + + public void queryDevices() { + Log.d(TAG, "Searching for devices"); + Set pairedDevices = mBluetoothAdapter.getBondedDevices(); + // If there are paired devices + if (pairedDevices.size() > 0) { + // Loop through paired devices + for (BluetoothDevice device : pairedDevices) { + // Add the name and address to an array adapter to show in a ListView + //mArrayAdapter.add(device.getName() + "\n" + device.getAddress()); + Log.d(TAG, "Paired device: " + device.getName()); + if(device.getName().compareTo(DEVICE_NAME) == 0) { + openTelmetryBluetooth(device); + openTelmetryBluetooth(device); + } + } + } + + } + + private void openTelmetryBluetooth(BluetoothDevice device) { + Log.d(TAG, "Opening conncetion to " + device.getName()); + BluetoothSocket socket = null; + try { + socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); + } catch (IOException e) { + Log.e(TAG,"Unable to create Rfcomm socket"); + e.printStackTrace(); + } + + mBluetoothAdapter.cancelDiscovery(); + + try { + socket.connect(); + } + catch (IOException e) { + Log.e(TAG,"Unable to connect to requested device", e); + try { + socket.close(); + } catch (IOException e2) { + Log.e(TAG, "unable to close() socket during connection failure", e2); + } + return; + } + + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + + try { + uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); + } catch (IOException e) { + Log.e(TAG,"Error starting UAVTalk"); + // TODO Auto-generated catch block + e.printStackTrace(); + return; + } + + Thread inputStream = uavTalk.getInputProcessThread(); + inputStream.start(); + + Telemetry tel = new Telemetry(uavTalk, objMngr); + TelemetryMonitor mon = new TelemetryMonitor(objMngr,tel); + + } +} diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 7f04e344b..b403f85e3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -12,8 +12,12 @@ import java.util.TimerTask; import org.openpilot.uavtalk.UAVObject.Acked; +import android.util.Log; + public class Telemetry { + private final String TAG = "Telemetry"; + public class TelemetryStats { public int txBytes; public int rxBytes; @@ -133,7 +137,7 @@ public class Telemetry { /** * Register a new object for periodic updates (if enabled) */ - private void registerObject(UAVObject obj) + private synchronized void registerObject(UAVObject obj) { // Setup object for periodic updates addObject(obj); @@ -145,7 +149,7 @@ public class Telemetry { /** * Add an object in the list used for periodic updates */ - private void addObject(UAVObject obj) + private synchronized void addObject(UAVObject obj) { // Check if object type is already in the list ListIterator li = objList.listIterator(); @@ -169,7 +173,7 @@ public class Telemetry { /** * Update the object's timers */ - private void setUpdatePeriod(UAVObject obj, int periodMs) + private synchronized void setUpdatePeriod(UAVObject obj, int periodMs) { // Find object type (not instance!) and update its period ListIterator li = objList.listIterator(); @@ -186,7 +190,7 @@ public class Telemetry { /** * Connect to all instances of an object depending on the event mask specified */ - private void connectToObjectInstances(UAVObject obj, int eventMask) + private synchronized void connectToObjectInstances(UAVObject obj, int eventMask) { List objs = objMngr.getObjectInstances(obj.getObjID()); ListIterator li = objs.listIterator(); @@ -235,7 +239,7 @@ public class Telemetry { /** * Update an object based on its metadata properties */ - private void updateObject(UAVObject obj) + private synchronized void updateObject(UAVObject obj) { // Get metadata UAVObject.Metadata metadata = obj.getMetadata(); @@ -287,12 +291,12 @@ public class Telemetry { /** * Called when a transaction is successfully completed (uavtalk event) */ - private void transactionCompleted(UAVObject obj) + private synchronized void transactionCompleted(UAVObject obj) { // Check if there is a pending transaction and the objects match if ( transPending && transInfo.obj.getObjID() == obj.getObjID() ) { - // qDebug() << QString("Telemetry: transaction completed for %1").arg(obj->getName()); + Log.d(TAG,"Telemetry: transaction completed for " + obj.getName()); // Complete transaction transTimer.cancel(); transPending = false; @@ -302,16 +306,16 @@ public class Telemetry { processObjectQueue(); } else { - // qDebug() << "Error: received a transaction completed when did not expect it."; + Log.e(TAG,"Error: received a transaction completed when did not expect it."); } } /** * Called when a transaction is not completed within the timeout period (timer event) */ - private void transactionTimeout() + private synchronized void transactionTimeout() { -// qDebug() << "Telemetry: transaction timeout."; + Log.d(TAG,"Telemetry: transaction timeout."); transTimer.cancel(); // Proceed only if there is a pending transaction if ( transPending ) @@ -340,11 +344,11 @@ public class Telemetry { /** * Start an object transaction with UAVTalk, all information is stored in transInfo */ - private void processObjectTransaction() + private synchronized void processObjectTransaction() { if (transPending) { - // qDebug() << tr("Process Object transaction for %1").arg(transInfo.obj->getName()); + Log.d(TAG, "Process Object transaction for " + transInfo.obj.getName()); // Initiate transaction if (transInfo.objRequest) { @@ -366,17 +370,17 @@ public class Telemetry { } } else { - // qDebug() << "Error: inside of processObjectTransaction with no transPending"; + Log.e(TAG,"Error: inside of processObjectTransaction with no transPending"); } } /** * Process the event received from an object */ - private void processObjectUpdates(UAVObject obj, int event, boolean allInstances, boolean priority) + private synchronized void processObjectUpdates(UAVObject obj, int event, boolean allInstances, boolean priority) { // Push event into queue -// qDebug() << "Push event into queue for obj " << QString("%1 event %2").arg(obj->getName()).arg(event); + Log.d(TAG, "Push event into queue for obj " + obj.getName() + " event " + event); ObjectQueueInfo objInfo = new ObjectQueueInfo(); objInfo.obj = obj; objInfo.event = event; @@ -391,7 +395,7 @@ public class Telemetry { { ++txErrors; obj.transactionCompleted(false); - //qxtLog->warning(tr("Telemetry: priority event queue is full, event lost (%1)").arg(obj->getName())); + Log.w(TAG,"Telemetry: priority event queue is full, event lost " + obj.getName()); } } else @@ -410,25 +414,26 @@ public class Telemetry { // If there is no transaction in progress then process event if (!transPending) { - // qDebug() << "No transaction pending, process object queue..."; + processObjectQueue(); + } else { - // qDebug() << "Transaction pending, DO NOT process object queue..."; + Log.d(TAG,"Transaction pending, DO NOT process object queue..."); } } /** * Process events from the object queue */ - private void processObjectQueue() + private synchronized void processObjectQueue() { - // qDebug() << "Process object queue " << tr("- Depth (%1 %2)").arg(objQueue.length()).arg(objPriorityQueue.length()); + Log.d(TAG, "Process object queue - Depth " + objQueue.size() + " priority " + objPriorityQueue.size()); // Don nothing if a transaction is already in progress (should not happen) if (transPending) { -// qxtLog->error("Telemetry: Dequeue while a transaction pending!"); + Log.e(TAG,"Dequeue while a transaction pending"); return; } diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index eb406923d..e2050fc25 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -55,7 +55,7 @@ public class TelemetryMonitor { /** * Initiate object retrieval, initialize queue with objects to be retrieved. */ - public void startRetrievingObjects() + public synchronized void startRetrievingObjects() { // Clear object queue queue.clear(); @@ -108,7 +108,7 @@ public class TelemetryMonitor { /** * Retrieve the next object in the queue */ - public void retrieveNextObject() + public synchronized void retrieveNextObject() { // If queue is empty return if ( queue.isEmpty() ) @@ -120,7 +120,12 @@ public class TelemetryMonitor { // Get next object from the queue UAVObject obj = queue.remove(0); -// Log.d(TAG, "Retrieving object: " + obj.getName()) ; + if(obj == null) { + Log.e(TAG, "Got null object forom transaction queue"); + return; + } + + Log.d(TAG, "Retrieving object: " + obj.getName()) ; // Connect to object obj.addTransactionCompleted(new Observer() { public void update(Observable observable, Object data) { @@ -137,10 +142,12 @@ public class TelemetryMonitor { /** * Called by the retrieved object when a transaction is completed. */ - public void transactionCompleted(UAVObject obj, boolean success) + public synchronized void transactionCompleted(UAVObject obj, boolean success) { //QMutexLocker locker(mutex); // Disconnect from sending object + Log.d(TAG,"transactionCompleted"); + // TODO: Need to be able to disconnect signals //obj->disconnect(this); objPending = null; diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index fac67cabc..b74df9218 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -17,12 +17,16 @@ public abstract class UAVObject { } public void event () { - setChanged(); - notifyObservers(parent); + synchronized(this) { + setChanged(); + notifyObservers(parent); + } } public void event (Object data) { - setChanged(); - notifyObservers(data); + synchronized(this) { + setChanged(); + notifyObservers(data); + } } } From 594978e2abd21764289b93e5a43de0f0510f686e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 16 Mar 2011 15:18:45 -0500 Subject: [PATCH 224/543] Update display to show connected icon --- androidgcs/res/drawable-hdpi/icon.png | Bin 4147 -> 48558 bytes androidgcs/res/drawable-ldpi/icon.png | Bin 1723 -> 48558 bytes androidgcs/res/drawable-mdpi/icon.png | Bin 2574 -> 48558 bytes androidgcs/res/layout/main.xml | 2 + .../openpilot/androidgcs/ObjectBrowser.java | 92 +++++++++++++++--- 5 files changed, 83 insertions(+), 11 deletions(-) diff --git a/androidgcs/res/drawable-hdpi/icon.png b/androidgcs/res/drawable-hdpi/icon.png index 8074c4c571b8cd19e27f4ee5545df367420686d7..eab1fc68fd7ad531ac025a53956f78de8d4e5180 100644 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 4147 zcmV-35X|q1P)OwvMs$Q8_8nISM!^>PxsujeDCl4&hPxrxkp%Qc^^|l zp6LqAcf3zf1H4aA1Gv-O6ha)ktct9Y+VA@N^9i;p0H%6v>ZJZYQ`zEa396z-gi{r_ zDz)D=vgRv62GCVeRjK{15j7V@v6|2nafFX6W7z2j1_T0a zLyT3pGTubf1lB5)32>bl0*BflrA!$|_(WD2)iJIfV}37=ZKAC zSe3boYtQ=;o0i>)RtBvsI#iT{0!oF1VFeW`jDjF2Q4aE?{pGCAd>o8Kg#neIh*AMY zLl{;F!vLiem7s*x0<9FKAd6LoPz3~G32P+F+cuGOJ5gcC@pU_?C2fmix7g2)SUaQO$NS07~H)#fn!Q<}KQWtX}wW`g2>cMld+`7Rxgq zChaey66SG560JhO66zA!;sK1cWa2AG$9k~VQY??6bOmJsw9@3uL*z;WWa7(Nm{^TA zilc?y#N9O3LcTo2c)6d}SQl-v-pE4^#wb=s(RxaE28f3FQW(yp$ulG9{KcQ7r>7mQ zE!HYxUYex~*7IinL+l*>HR*UaD;HkQhkL(5I@UwN%Wz504M^d!ylo>ANvKPF_TvA< zkugG5;F6x}$s~J8cnev->_(Ic7%lGQgUi3n#XVo36lUpcS9s z)ympRr7}@|6WF)Ae;D{owN1;aZSR50al9h~?-WhbtKK%bDd zhML131oi1Bu1&Qb$Cp199LJ#;j5d|FhW8_i4KO1OI>}J^p2DfreMSVGY9aFlr&90t zyI2FvxQiKMFviSQeP$Ixh#70qj5O%I+O_I2t2XHWqmh2!1~tHpN3kA4n=1iHj?`@c<~3q^X6_Q$AqTDjBU`|!y<&lkqL|m5tG(b z8a!z&j^m(|;?SW(l*?tZ*{m2H9d&3jqBtXh>O-5e4Qp-W*a5=2NL&Oi62BUM)>zE3 zbSHb>aU3d@3cGggA`C-PsT9^)oy}%dHCaO~nwOrm5E54=aDg(&HR4S23Oa#-a^=}w%g?ZP-1iq8PSjE8jYaGZu z$I)?YN8he?F9>)2d$G6a*zm0XB*Rf&gZAjq(8l@CUDSY1tB#!i> zW$VfG%#SYSiZ};)>pHA`qlfDTEYQEwN6>NNEp+uxuqx({Fgr zjI@!4xRc?vk^9+~eU|mzH__dCDI=xb{Cd}4bELS9xRaS!*FXMwtMR-RR%SLMh0Cjl zencr8#Su<4(%}$yGVBU-HX{18v=yPH*+%^Vtknc>2A;%-~DrYFx^3XfuVgvZ{#1tA== zm3>IzAM2{3Iv_d1XG{P6^tN3|PkJMnjs&CWN7%7_CmjoVakUhsa&dMv==2~^ri?&x zVdv*rnfVyM+I1^Kg*S=23mR@+0T9BWFZUu~@toA8d)fw6be=`Yb6DSX6D?jB%2YT~ z*aHjtIOozfMhA!Jd*?u5_n!SnX>vX`=Ti-1HA4RiE>eI3vTn zz+>Ccf0HX6Ans-ebOB>RJST-Cyr#4XAk+mAlJgdQnoE{^iIN)OcYFSpgJUmXtl@tT z-^ZuUeSj5hSFrQwqX>~EtZ*{>Gi8Bu9_|o06oNtaXP?E936!a@DsvS*tsB@fa6kEA z5GkjwmH?EgpiG&itsB_Tb1NxtFnvxh_s@9KYX1Sttf?AlI~)z zT=6Y7ulx=}<8Scr_UqU-_z)5gPo%050PsbM*ZLno;_-ow&k?FZJtYmb2hPA$LkP)8 z=^d0Q6PImh6Y|QT?{grxj)S=uBKvY2EQUbm@ns9^yKiP~$DcD)c$5Em`zDSScH%iH zVov&m=cMo`1tYwA=!a}vb_ef_{)Q2?FUqn>BR$6phXQRv^1%=YfyE-F$AR4Q?9D!f zCzB^^#td~4u&l~l#rp2QLfe3+_ub9@+|x+m;=2(sQ`s%gO|j$XBb>A7Q(UydipiMw%igcweV#Cr~SP);q>w`bxts_4} znKHg?X==JDkQl3Y>Ckt%`s{n?Nq-1Fw5~%Mq$CAsi-`yu_bKm zxs#QdE7&vgJD%M84f4SNzSDv)S|V?|$!d5a#lhT5>>YWE4NGqa9-fbmV$=)@k&32kdEYetna>=j@0>V8+wRsL;po!3ivVwh<9tn z2S<1u9DAAQ>x1Sn=fk`)At|quvleV($B|#Kap_lB-F^*yV=wZ{9baUu(uXfokr95^ zA*!*W=5a>$2Ps`-F^+qRQT^{*cN>vipT*4!r#p%{(#I7s z0NN94*q?ib$KJjfDI_sjHNdmEVp5wB&j54O#VoFqBwy)gfA$%)4d_X4q${L9Xom2R3xy&ZBSNgt4a1d7K^CDWa9r zVb-_52m}Vp)`9;ZSKd#|U4ZYj5}Gp49{4utST|=c`~(#>KHF6}CCov1iHYw zt{bWo)A@yF2$~c(nR$rSAaFQ$(Wh{vkG1AlutDMw=mM`C`T=X&|Ad9fb5Od}ROt1z zOpczHqrb4Jo^rSCiW#&o(m7jFamnrsTpQb;*h4o8r#$aZ}2RaT-x2u^^ z%u@YyIv$U^u~@9(XGbSwU@fk6SikH>j+D1jQrYTKGJpW%vUT{!d}7THI5&Sa?~MKy zS0-mvMl+BOcroEJ@hN!2H_?coTEJ5Q<;Nd?yx;eIj4{$$E2?YUO|NtNPJ-PdDf;s} zab;}Mz0kbOI}5*w@3gROcnl#5)wQnEhDBfn!Xhy`u>C}*E~vWpO^HS)FC>8^umI=+ z&H;LW6w#;EF`}vQd_9Muru`KnQVPI9U?(sD)&Dg-0j3#(!fNKVZ_GoYH{la~d*1Yh$TI-TL>mI4vpNb@sU2=IZ8vL%AXUx0 zz{K0|nK(yizLHaeW#ZhRfQXoK^}1$=$#1{Yn002ovPDHLkV1n#w+^+xt diff --git a/androidgcs/res/drawable-ldpi/icon.png b/androidgcs/res/drawable-ldpi/icon.png index 1095584ec21f71cd0afc9e0993aa2209671b590c..eab1fc68fd7ad531ac025a53956f78de8d4e5180 100644 GIT binary patch literal 48558 zcmeFZhd-A8`#-FdnGq@^BP&}Wxy(c%6pCym+50Mcg^-cGN7-B1dke`XvNu;UvbXy< zy?@{P_q*@=U$}dG-jDbDbDh_9p0D$G9piaCkLN4Dr;3k=2&f6Lu&{_^Wu%m`u&}+5 zfADbNlYPZgVffbtTS?hxc<{#=@3k-de|#$$bz3YfiYDZrb62bsB;i9UwDb$Kisc)$ z-Afw-EIT_pZet5mTm6?-2Hci5hHvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 1723 zcmV;s21NOZP)AReP91Tc8>~sHP8V>Ys(CF=aT`Sk=;|pS}XrJPb~T1dys{sdO&0YpQBSz*~us zcN*3-J_EnE1cxrXiq*F~jZje~rkAe3vf3>;eR)3?Ox=jK*jEU7Do|T`2NqP{56w(* zBAf)rvPB_7rsfeKd0^!CaR%BHUC$tsP9m8a!i@4&TxxzagzsYHJvblx4rRUu#0Jlz zclZJwdC}7S3BvwaIMTiwb!98zRf|zoya>NudJkDGgEYs=q*HmC)>GExofw=92}s;l z_YgKLUT5`<1RBwq{f)K~I%M=gRE6d)b5BP`8{u9x0-wsG%H)w^ zRU7n9FwtlfsZSjiSB(k8~Y5+O>dyoSI477Ly?|FR?m))C!ci%BtY!2Sst8Uri#|SFX&)8{_Ou2 z9r5p3Vz9_GY#%D>%huqp_>U}K45YGy__TE!HZA@bMxX~@{;>cGYRgH~Ih*vd7EgV7h6Pg$#$lH+5=^lj{W80p{{l+;{7_t5cv3xVUy zl_BY4ht1JH*EEeRS{VwTC(QFIVu8zF&P8O$gJsMgsSO35SVvBrX`Vah$Yz2-5T>-`4DJNH;N zlSSY8-mfty+|1~*;BtTwLz_w5 z+lRv)J28~G%ouyvca(@|{2->WsPii&79&nju7ITE6hMX4AQc{|KqZN#)aAvemg3IZ zCr}Y+!r}JU&^>U1C2WyZC<=47itSYQ`?$5{VH?mtFMFFExfYTsfqK%*WzH@Onc#i` zI@a|rm-WbKk{5my{mF}H>Duc$bit&yLAgFfqo2vVbm~?FeG#0F?dSP*kxSo0Ff!o@ z(C}B;r&6pa-NY4;y~5lX8g&*MYQ>yLGd^tDWC4(sGy$Ow-*!eh%xt;>ve|J1q$*w< zh;B#cz!6l2=5bkX#nJ9PJQ`ew8t>7z$bxqf*QB=l2_UB$hK|1EIfloN-jQ=qcwChF zYAkkyp=;FwcnUB3v0=*tMYMA(HdyvMn~f> zkcCRha+`kU+<0%c&aJ6q&{105R%npN7rTG_G8E^PemgCOk8g5umPRo$HpcKH7e+Lx zdw26&a&M-*k%@_1!~kcOjPi7=+ZC5Ty8Qvo=in72{%$=+v0#=mPPWTVPds;acFvK% z{Pm33OF=$ewwBEa-W?0e_eoReMEF)g=t*8pO^sppgnb`wV|seJhBhVE zT4?dpP<`b|Qsj$dYEpfUvOIDJLvTaUu>Ch-cS-LG2ylgNMTO=kgbO0yai7~wOwAaD zKPY0h;4mf1pCMG6mD`T%!W+UG* zj!jK^tl=nd`Rp$EPLKMsVVz-W2j|s9&ek#L9cIa%ztxFY2up4Lb86Md=xCWv`=qn9 zngqXqz&KZy!X;1SqMovMYUwA#V*I!sf|n{PVQGZjgs!@wZ<#IekjuUmncP2(k*ABT zGFXmbPq#KriOU`|Mhu+Ynq~YnWUI&Cr_s-h>NuYg2lUhf2Dn zqf%!dPe?P5k4{XSbaWgyb`X2fC9#aKunF8XM;_xYdzaq0cV3b1_@~GEtP_sl$Nv9* z)JqdSu%W(7p|e2+8^uz_t%cIPyvd3Drv7zK@Yd!h!z%xS+y@4=9LC1E{>bN8DsQsH zW`kq=EvU>*OxVMV)s%nCy**oQdj03rSg@3S(uug1iTC>9E6NM-1NYa#$%K3pbbFpx z5O1IgEtR!VaJ-7#OOM@)xzpIva&7PUbmJ9=mm9-}`^e`qEZo}B+hWt?9EhX&Gu4QD zDPWQvNg<5X^_vxlz%$nWVcS}Ow#oaoOd@3J)s4QoL*mT*dM3vfJ4N9Cv9Ylm%r^$p)|in6V=?*orY6ISBu)~$+xfmc z^Vz@kUkLf8);>ri(w%+h@CBQ!s=mH{cB)FK^BX7RXILt)Unu84P%ip!r|K1*Lt}4* zew2?oyO^#O@<90u21zSe_2C?^>CbNC#QwVD%oB&nH6J2YtWSTzaCRl`mG{|$&9ZwK z*gDY{k>Bb4NE4F3hWr=SPrd(c5clf;|2JZf|BoGPVu<16Ym2*w&tJUAY;2UAUtH{1 z+wGYB*9QMv-u|(?Ef;!lc*wIq_l%THG4)XJBwJO}{nB*vyO*rv=Mh%243$-G>T~V2{)s92{cB z-D(%QlM4F!`q&)0pWaGcUA4Gz&q`vn%yMX=#z|fJ!hZ{{cP}iwGw!gM5G!Pxj-enT zAu(O-N*F0Mk9+rb_=|_fxqewJceX}w*LsQ{-Q7bs?8d$v95|{+8lVG?N+r!w|X9I z>^rBcyn1tba_o3|ygN8C(Ur}B#dHrb8;gg5dgbxX=-UpivgY}s_uqPkhB5>v>>sSv zoz^~l^a#0IJ{C3u7FO6)qSI>c#(al@p}gP8iRfTH3z7h{c45Jn)s#>R83W54GCR;!&wq{nxLhENl1E zb=;2MmWG~}h_}6Z<%-KB8p5glb8fD@?%~MLoK1y%2Iag>1;r(tx19n*Mpjl&$H&Lh z!?3WT>cMalm-dcbMfc~z$G%L`ThGha`Eoj#q-|Y-r3pNcM?L-?Ck8wGL5?8h0;~9>aYHH zJ(pM!DlCQQMjN9U!$o&C#IE%hDzvyuii@MWWE?x9c!tQIhRrKfm z%|#9YfkE^Ku4k&Me_{+1d$%zC3K>`u%4dH19&)ri>#!WWc*-ZS>^RHX-)I6XrWt&I&w+TUEf&2ovQfO}N=iy>s>aj#%uFY$9UKoZ8ITf;P#3X6 z&m$HguYZfTFh4(UyfRW^VrIsla2^Z)6XNsunK?Op30ShUpC0KR^hFh$46+N+9Nojl zQu|o&84D{wMM){7u&7AEaB5e}?ReYq=wE9@NXSdLG1-}^XPe*k?mg4i&inOCb#P!H zTJfB_R}*54d!31*qv-S845FgipG0?}^XpC=5mP)xOhM^0F!1cTs%mUky`j}T8jTW@ zh}x|*p7z;)(OqzZGi%<1^wVC**-u63^Zon7Jnbsg{r!E|0{Ye4$O{vjT~pwMZPKWE zm-lCR8L^_4K19^i9U5YvH=VHtC~We%&Hb(QCK6Nd7A=Ky;QeZlytq>;D>Yo}Ceb+g zJqm*3sp7}|;?L;sg6Bda^gG zQHjpNP+<99N3J-37#q`4%#pvz9rbv3+%AdMafzW~+yY`;j|Q=QlE+GNdsbSS^b^tT za2s1&SgO0y*$;6_{aFfTW?q$)mfqRI{wjcMGtUR7qz&v+q~yu3V! zSUz|=l@G`T|F4{n-@bhdzioki-9}vB|0>rV$kYLo;x~LVlGimy{p=u@+A4w zfJ^tfgV#N^71>wmui6ywgTAmQVp)Ixn!%Rx8lS}kUj9vYrih4$tdf%Fe1=_!i-n!t z@kx7I+f!rXEX<{5KiGDc<7M3;uClSlK?^^t2G zh6c-*3VB~K@0H~8a3R};Ot^JROAF!zEXXtWM8V{IZ+`M7c-)JOi_5WeS=KZ$Hogsy zRtrR4W|I68&iuBcf+2mEg9t5>+BF~r#VcmOy~|%AdvHWs>i_B{l7v|k?ImMkV&LXe zACZt+ccR3*tpqP*Vs8GNmlAm&^6!WRS_udU!sFshQP}ukD}~9u?}F&rK*3mWef*b* z2kPe%&zRh!As%7Hyvz3mp=U3Vgs z7@NrB_GievGcPHLBFLft8BLaeZ}#cE#i@--y9#yx;Ib$mPx+%l9B`AMXloLqQJ zj4=v(Pd+Uz4eQD9?Z1EVorKHHQF=g$T0Jd(`L$x$&i&5?Wj7?Oev+1Z9<<>cru-yl;}R18XV z-jL|F3|}kyJTDt0R&Wh&(WCXI-1pd&g2+Ylx%qiE9v-+WZ`ML*Tt-Hc ztA@0+G#H%;>+CwDi+3SWQ5hMDj*y@f;6gK!#N5r13p4-hw_12yl@QOGN235d`Kp{P z2B2MbR@Uu=bMh6-`BjRa#81la+_?i@>HFa9dh~65oE)aFdEm;BJU71Jxr?6}=whjV z<7!`jKN1GU`y2Df;}DBW^c8XXV;f*;m&eW^uq>+X$iSgS2V83g0c-S_h^QzIBy4a< z1pyRq4X8X}6BnO^C~86yjjZL)-{0xv?&T_gvysrOt(|~to@dvfj+Wm8lmY$t*QeZ1C81UI@B8)bKuc%Oyg_#&WJ5x!b3E(!E_mLDH^@d% z5P>@z0&HbWE_v1O8N7M($B#9!r_i7SUOW0GytaGl{JSav{qL9Hc9O8$NG?N)4Wu@B z5f&=sMT{?c-go_cG5_h~$Nsh3d6sN~ft5SEL&>Y7azKSVE*2Iq6#*e(L|B+U3OlN|zdt1;85y2S()IQf|!ViGytJoFTP3u-ni|gEibRB z83#TiH1nyWZ3D>Rcp05u!-REn@)NJ;5`C@ zf*fRiMw7KJkfG$y0wU{~nwlx5FAV_Yitfq0Zn1tVG2`0tsK;E*?nGGAG*Zx^j)q*V z`o{Sf60e%NdJOb)4YuAA?~%raDI)E0luc#k{erra$_eL9g?=hn%%7#Do`db>h|thv zfIW)L2{)mUG%+%IYG{}NeJaF%`6VP;mDK?eLSrd!INZ0hGP*rWcRGyz&Uy)Y$K_vn z2Y~4!Vq&t8@+n&y3^(&8yp~;7riOGmwph+MX93^V-rk#FH(`uwiaa)bk<^A)f_ARv}# z#jkneRd#WTlx0@;a&?dYs2z0F9d)pY;tzHKEE|LpHZr0CZYAb@1$l39-^$aIL-l{R z>8S(%WQZSUNqz~&gyUn@*3`fazkmM@Si5sAL3Ux=aj>s18E$%fxQjgVcJ0PFtk6bS z2vQWlZXt}1&Vq3EBQ()98$UP@kAJ&9b-!OowtLzNX`%i%I3b1Z%bm#@U`%##@c=X^ zF6#}ruv@$d*3Y|=#0$2UhfJaM6c7*?)4taZ0O*;nZh@%N&JvgtOs=U9L{9KJXU7aL zl_!}C&OpU&4ET`T2R^nkWdbbCPMzuse*8hMcy+w$O5j5U)^nvz1d!{dtt&HyaEWPp zmXsQyiD`%C-=PR|SW{#HZRd5eY7RYo%2|04+uRJA`*)s*d1LW9Q@RhsWk= zmMJ>zt_mdFHin0lyllcr5Vlin&Spg{vP+Pl8an^AjS1;Hr6J@AGC zmJ=fVRHgioA(D>&8kRb&ni?6&To<$en6>ZYU-TTJ$}<)oL49)j9P*<|y+eN!?W%6|@>FNT6X z>zgFF@(VDc>95@B3hoCJF1y;J7R%RZX;qz^suUAYX?nc3KDFwj*w_H#7*98P|G{9C zo;>-4p`m9(>J*u(xq04I9vw4OQ>p7ef8F5|<$u8Sm=Axw-=D6aa{s;uSQ?yepr?nv zY&5T{OL5dp2`8NZA^Y(CSCSXv!KUyIdKR#6V+TBl2Rm9wY5 z-o3K25}tR~1_uXU<<`oC$d2v$nzxwbrqk5a1UFCxEBq?ZEdXGA<=VBlE?E?0S4htY zHhZ@+V$jiV;ql@nkel=j-?Rtf$ypVb04u={C*bxcn4}X~x5F~GoZ4D3h&jZv2fxZ{ z)1X`IXOn0|xX)lK=yO)9*2Iu{+Y))#a^mL=XL75VW_-jmJtQPxN78LW6~TS4a=!SS z^5_#n(WKk{*JI1vvt8_ZuCJehxispyQZj@-+OzJb!e^!-HU+{AWi{n)Vq!A4d#J$5 zd<8ZJ*l+d7G~iNVyUvjjU^D2k5@$3YE6AJ|97l%%(1oO-%uhWCL`lZeTVQF11k_tO zNVh6-avuRmzL*bU=qLnE2^=dQ!eqmVf|3seu8{Vd9wjAoa?4%F-=6 z1BTo1FkD)D3EEGs=#N}C#GGGP)@(;&0=%vg`;>sEzJ2!&`rL;IEDj5m180Q-UTn9f z1Gnx%6O-;z;(5F_5SruBP5xg~IC(_zKgDJc&iIi9uP;rvh-5k?K%<}Dg+C2-LSS}loCtHlcuy?f6M zxEvnVhF-L>KOc4M#F_DEBAF#^U@W^$rcTmu=kW~HgXXg5IjU@;qT~NNFCOWM;zJ*n z0+9|JlPaNpE^vKCZ#w((wX68~`Cp@OeTCr>=Zk2#_c`*_e$AA~S=zr?jsMK)W7}9T zyPo<(w^r(8BaM1lJlo1`mucX<8V?_z3Wr)gf5J;m$biqGxL^WOA)yTP_I}Z>dY6@* zEe9nLw&vlRH|ZK08tA#U%c|ubPh?{~dSD|w)N|(L+m&ALSC=e5e2K<@9F-!DV`h@Ln8u&?uGy!e%*JTfS?3*9U(6`W|wk^0}bkiMhFX zA?IT#rMXwX`?k(10d9pVSL}A`+AkzACKKynWwstJnX!B8X_pe$GzwR(WO^m{)TekoDH?9c$m`;oj!)O^xUrQ91=TTbXXAQmSI_7$~@}tAQ z6PG@^{Qu6_X3(D*btj6B)VfqbE&k1NgE7*;_+Sge&c@aYiRucm50skk%$*XqWP86| zCc5FQIbEc^p{B!Q+2EY^Y&^4Ah@?%;CQ!>ml8w6N>z~W>`?yRv9T-))Z2|-B(d=Re zlJTpc#@Ey5iM+Ia(1b{*6Bx6rZVvM(b?SAHS=8(Ps>lRtl=rzhC;WHX85hjzNk zpRo#Cpr(O31%MGj6O^@gkaPshwSe1+^UCj{N5{v9dS@m;|%ELLX%qT|YN3eA14_(oUI4ACW0#A%>>7MQMovN`73bx0D znx;0{+?#KY%NxMh$$q?rb|hg9ZS++ydSeVkFTy1bQOkT6pDHV4pp zI6?ukv8AS`n;`XKWo5881);vbGtDE$S`Yp}T%Gl8vvr=!EO`Ft6JY?C&*S{9SNk7h zBT&cO7vGFCK3TmaRBik*2t4Blt2A$`Ca*3P*C%$<-ZEs_^BXaWq3CHTWnHBrWfKd; z%_LoLoBdLwen5_VU-LR60Cn zHfrjDsoEh5sy`8BdbOMxhkR}|O>rzw6!VU*46&JaQSWy|{fN-H*6Xb%uI+5|G&Y*Vn&7g|IKZi&I!wH~?_+fe&$3S=5^GR}!E^>aL(_G(B-Af`x@| zseRUqcZ*`q5Z6qs{w%)a$rsEj-FOX0s`Q$kB~9K|{fy*e=KMriaizY6@;qqui$VIekne-Rca4 z<_Rd;G>1PAjC8Z*t!{42bw>6_Wyu&l4S5+f`@Kbd_1VQYV`;f*Zt3;8-5n81)McZR ztX-kPRSRGK8SP+y{le~Yxb%zNx= zH*c)c$&(5R2{{5VS6BKJGTZuT*+=~7i=(3>@B?Ar-*I@=@!YXd^h~IW{QhvBEt<8X z^5Dq;%_>DjQO-P6(fYrK;mRdis{uCc)2gqR_{C{Pz2}1q%)Z?z*iXL`OBcavw_uQ@ zt-uo5&!KDWubi!R>yC};7e0Uw3?73+LjYqY&>zf^c63lpS0KT|8VYvb2cqlf)iEJp z9V)cQNAbO%5L`H~@m0@5F;OH7mI$2*i+3JwBVjW2%J1yye7pIWyP93$@zJ%FO;K#! z#W8YO8u|Z|M~$UJlRsWc2u%)&uBH2FW8WWvTGlb(InIZAf3%lW;-Y;o1pV8aT=uX^ z;8(Zklj!m*9IBa_Z4+*h@*~v_MbLk~1lAuJTf#U>;^M`Nv3Jd5G4Wmt|AEtjp&V#g zpdJJ5Jl%S;$&i0|pF>v3VRJ$57t`2^zPe4iVwj*?B4nKBdOOD(3*BLi%xY)(v)k8c zoGeUOI5XgbPejSw=tcx*coR8q0)<*Un~+>qg*1c(!S3qe-Y&|@;s0*I4|Bh^#;NJL zM6B50o7mgGpmSdLaCCBlV%w3FlJo5ObAaBNH-z6Ap~DyFLPX4tFHNVF+nRvibVI6% z@7oOwh#zeG)=4eoI8D{eyIa*F=%aG7VLG6A) z%?Yy`PF=0tB~gn>ZGNS0V~EQWFY{+XO4+&8pd%7c#1HTppgS-tWs|^dQ&Lh<^`&4OV!0Uo0yQ?rVBYp7b6YU_vON51`z!be-2)|?6DlCb?X#djDdmpE*`0SA$XUDYWVLMu12b8{o@SgFN$_EX=m zxsYf|yjDh3ddMmfwdhGmwfE-iOg(9bP1}`Q!DV0XXO$$WXpEb{`Z_Qj&wwjy28k5t+f*lBq(243oDKg!i~~2?lp80UlQ8zjx6MNi25Q*z?V`2Nn?O za%E`d2i)10yUPA{VO%c3HEK-gzK}@P$AI|f{LLO%v(sGB837BABHngF<&Wp-nCDA) zP1vNpX0+EM3|nJ}u#xi%3rJ%It&7QcB{I5d2UbMvV2SaDkc||WMvQK9H(v^-7)ZZ9 zRex@KX9s#57B3I07X*o_(N zUr}T#zo-@26vY5Za6^q-4S^RN>P%`HUs5w68qFM{eK_)Dj5kkSsCU$IxXlyU926r;9m-R5IG*#GkMUl(F+3 zo)EHTrO(|$-97l%K-=yp5y)(5?SJQ*^Me>dx+qq+AWl}2{x}L$k?vyIX)~yvCS6L79)gUGO8;5armHW0QVu}ON&HilRR2R1xwvH7ln z&SokAp17_U-VRJeS*H3#GGWs9M-RJ<=Y|&uhb(ADQ`ajPKM)oq&MPXJbmqw=IDFEg za<=tnWqc&go8W#=U;V02J7uY1H?6C0Nd+h^j^|j#dtoqv3^LhSSz955j4dowp`kum zT{}@sNfF8R+-o6t86effNR8TyY&5JQJK-hkn2!)HlC15MCitn5HZWywWB9z?W}kv; zRfS)~3}rp0MKupSuQU`VzWpCjZPOjR30_Yyr%P@eW8Fnp_ecy33=m}k=8~q zzkXq^D=VUI29?%Xp?mVtz$PuKt&j#V1haHwI=OheO`BS!Ow5qTmw?DeP+cEK_M2A{ zT)TXOFw62-w{>!jf$}YI1MHNS5S$E~;xW7VPZ(5PBj5CWV5*T48%v#*{(aHI@gLad z5x{2zuTl|Qj-te4z0WU_`sLWt$ZV>-`XW(bJZ-=1?bq#??nqY4Qsrz*RlP3kjVpp3 zF|mLGsjs8Bs2mrXr)5?C{B(+_*{XuwDFXl)y2r$q7`S8BJCzuPOk#nJ7yZ$uComZf z#7NCn-(v_WA1I64P@Xzg-sKb)h7LC3w{>-?@=^{UsvoOplKYo+VL3|w;dd50)xp*# z*^O_UKJgysA+WyZ z=I^iy{*j_Va9Ej#4?nEd9$L8e@EdhRa*Y%k_`{4k3#dzIfQ_N`0SSmQq6`S<1$_KW zQ!}SCPLPk{WeVxf_dgy*5o^VfR;&~b&iE+@~U0Zp>&wx3Vys@BZnQ~i-}BfKdr zyRA(~`oZmy_j6W1bX^kwYen9Pr43=tP>uBD3nlCPy;G<1dZ`$m8v?koGeLL=ia^c& zLfqJw4;_$QRiH7CS7gocCJ%axVOt*a-D?}^JJn*!7+`>m<&64`F? z)9Qy0AHs*{5cSnWji&IszfYkR?du!m$Yad;!*2bEiQMgW1Is`d6bI1v6Z zuSlL>f72Ewta9>W9@3{fbXIe69N`qtUoVAI)a>0}OdN|jtJ40O^BfkDO`X^)einP{ zhY)$CV1mn09ccolzuM*tCx^b#|9=Q@-x3+?_>FS^hCF{sS~|B(V!-5SK(EQZ27D&6mOGurCoC% z6`%;a`6^vI;Fubp1*UiJj@|sn`O;(vhIHL(ps@xHZX~CmHajtqwx3Ey4|;t>r3Rxj zm_w*@RR;ifh{&)&T9vM%r+>sIz(%cf`s*|$jOSRKAYqkXo7|1l)rlo%{Wo_Y(fR{c zG2^qrr5P8QUuIF*nsm8ih>TQ0^~T3UmmT#RBKAFK#jz@|af$Q3O+VGw+paS~*Z}$8 zZp;^Co~E2~Ntb`6Xt$hO!c8Y9HT)mlL(?yyPS0p3Y}vWtZ~6y0bq5^B8&P%7Zc*Gx zARj_vO7X>q+n2noZ&KqgkNKQ_Cg*W`K3(ex%%!Y=bMZL({LG~s&joNUkO+l7Wg_c^ zIlz~?J^#9%lVcbIHFI?oo(+Z({!>K{X1>-eXvZ?e>MiDk$(^vriRJiA#ck0KgUs)0 z-?jk0{;(vyK3>Qc)Kfa30K{Bi`i79P1*ZoE+nY(JS}7^yRW?7kMQA_KI?P=ro@)r7 zeHvp=5oiQ&22C0F8OlWWOH2F=NF2`h80U%YqP*tQ^kvO?Q5ZVpK46B?K*~b<-oCbL zy8UPH(gcpTBm*+C_$akUPZqX3)!_L*9V;>^WnJBK790Ha%VhR@Aocax+c)Kja2oI3 zy=x^2{aNU|Y=q&6yzJ3euV%rX{lbTz++L&fwSd(qL1UERm9r`;)PcD~xgM3n=t@3= zIRbi=EJP0SArEL%ljDQ!bUrX5`&X^+DZqWbDplg)+Z-wK}1-z6y5 zZoUkpQ7`CCZA-;LC?P}0$vpgY<{v|EL*{b0(6 zUg}{;^r;|#z6oX&A+58w6JD9})b1ri)B_%c883e-fOVMbJ^`?2Q8tQJ9s_iaz?{KJ z;9M@s26^y?NJ&zQ9o0&*+WpYHr%P;?jk&2O`QcOUP>+Y8f?_d=`>TY@76SlcWlbxG8 zQ2BP5B9P@fZkCMvB`^G2W0QFeUApa11MS|GU}*HlaNZqjeNpkV4t)tT()_B`%8nBh zBsQ4yacLCGFfuX%oq#u4&Z-CF)$II*Sl`Hx9zk2gu(u9!LDOXET3TzjGLf! z&qz#6l+Ario1>bitf3K$pc2rT0`LHl++G6Aa`JTRbpB_SLo*9y4*_RqL_9$#1w557 zX{B#!LboGAmC5dnH-=^^^!vdl%-Ew-Bb5G_YVHeb>CwpZ9`49+%XUE?p$LE$340nv z0}`{hK+MBfy9U97FxX4ybALj4dQWgfnnbvnG`C1UQXMq(q;L zmZmfbl2$^YkBRIsMd9yZLvrt1pN1*V>?`$1z~Hqxs4;pDj>n)!QTN%iH(fb zIBX2Up_H4TaQD16M^8RAy7|x>^qE3l}o zz1K_4QnOxgOa()%Bx9hf=v?={R9018L3C&%o1SYRSXmjX2qX8nY0>U#~%3jb1NiqI0J>-yXC7X5p05cm9esR1hFjS9(DpL$I2$*1y~2 z5G=h2^_bCbjB5EcVLwZBL)38q#5mldqM{mQ772Iw_{<&bvJBKgTc)b1d0q3-Wl-42 zvJZ@A0dauv(`vEEQ^f)j|Mb-7Hw*nb0lrYx)z$TCQSj9 z>DZU{SpPd5aBsg`zI$piH~a?nlFWY*m#201AJT9`$Aq$5jfY-S%y{ieK_riEKB&jx zVNiZ=*PI+IgZpsU{Gao&9Y^`}>T0d!p@JcxGcgoQ_&Ac+@e=;@K-|x_XGQSU|Lcr) zJf=I5(O)E=rTzdy3`Ah8vY`W$Cq#Mxf-c4Qdtcyy3Y){E{Z|l&jk*-lSpuv`g$Ri4 z!peUEZ(nLYip(U=TB@D$_rMPzGUT&59Lz+CXMXbx2o>ByIqFQj-!G&QDf7&_OhknF zdvMAkO+M=Y8rJX8V&eA@{G?HC^#yAE0LVg4PMXVe{>eehxRf4eaVO!W6H=UEJwRlY zn`9^^C4D;^YB%#R~)0m9eT)|RchVbq%}9V_MnGEYr^shbCwCvGN( zO@YB8uuLTO|IgtZOGMLjaQ9+Am_R;*9-o(V%}-{}*exJJ+5Q)}N%0!jt{;7x(l*$aHf#Ush(O49Khn z6Bsa!eyNbmG^*{tfqa9QPAs0HH30Ygxjc;$_AED<#}}^OHS0+fb%HDq_R7pmUf6E+ z8K4A!RLIDgRpH}gKABC_t^BLlUpj%|(t5!aKGzw?s7~A@EyJSk$@G=nS)Da|nDPINojPkmvH!_5jf4@Qwy?^cx05PP3I zYfHF+Ix_hLjVo-Q$2S_UNh;C7FXTKfvWsQMOfMC^q@1sdRraDA%VA;*K%$>2>bbIV zGNJ=?JIHX0wX(AmO6Xz}Z@A)yNQ7i}wb-qMa7kzfin_((!aY^s%olR7!jRtMHt7s` zvOYtC`ROToW9SpR^Qtd~hN(F7VNhvY5M|l>_wT(NyIzBM8PTVoDM^2{%LW*_o0^!E zJMj{u(dcMJtN=Wprh~(}QzsbcbfM+sLBBfwZqyvQfO<+iYo!#{QcSbI?m&J1H703= zMf!8zj=Su4#tfklfwdJ_<)aPMO+b*kTe~Yd4mypqk?dB?%*wue6(aD#T&RzR4$o~r z%B^>~pw0rtoDO9Rv`~hi=ly7iXKftv6@d*#-B*!zVOlnRkUUzjcz4iCgP|HEeB?X7 z?*cLetr{XO4F!2xez~)l8DK(d@nV)LIL~rCbFGdy;T+`Dv-XhlE#jza!> z_cB2o(a$C$kxM#L2;fz)$gd%4^Y7YM7r1QN>uc-KqK2Ju0&G4O>n)=z~p<7me zfq2@thGvm*QWaL9dU_L^E3RdI{!E{xnAq|2=K$StFC9jBazE%yP4XyoCcSCZ-j#GO z6&a60yznMmCPxqfP!%8zrpJ+#Z(9%9M*Zs${{?d@aHJsU=#|iB1L*JN%uRo$S}3kw z{e#G0k;4|xpFN{Ae@P!eA|j4=^o8zpuNBm8Q6SOLiy&14O*r{gs+FM_yA!RNy8R&F z;pG?UiHYorwD}W34T;Ev4xpLHHHPQ!A09f_dX@Jv{)Q}ZrhVXZFXw}qJKgcpBa{u( zzb9&zMn=9ltrvqS!8=+$5Z9z6>YjZ2Kzve#p=ge|oJbe&7=rU))vhiFj@dlHT>TAT z{s#uF`1^2r=EaQ*+~%NbI$b9@{oLEz{CnKyHnf%a4kmYhzM^k_?ssW7Yd23^1rGN} zgoN0p+mhnKaw-0dBkl%HACZ`7fztnRFF_H}>WS|)kf2A+%itIT==KV=`Ncr}n6%RD zM}F|T+w~1dkA78OwfU_TZx?s`naY4s*Eo!; z4;n~ZKSRoHn~tuw#0BZZRiBvVb0<_-QA0p8!sDX5%GtNKx6jT21WT0rklrRIA~H5Q zU8cT%k3o0ZS-q=W*FoY)sBTsWLIfI`viXiEPJ7w|ENLUQ9r_!T$>^wm4_vc}pTOhzQh>2J`FJ zVBz9de__t*2u%@yRs0OlPr?;AfhU+?BaMTDQ*1s8NLvQ$l2b{4U6_y3RkgG%07*PU zg1DOwe9V697H`6xmw-<#tN(pK)SeWG9$h{L7?ZTF7i=B#0txSB=e7*l(j2`-`rojl z9Y5VKrsyWosem(IAo$gV;Q7@a#tQWq6J6H||Fu2gw3Y=H1b4}u)A`cds|3nE z@mXBSDRvO8vd$T-f%AeWO9do;|LchfOVL19!e}OryMe+gEsCA@m|N&LhFY}ZaqqWb zS~;5%i}Golvtfda5hSJm2Wo^sX$67j7UILuWq=QBm5SW2vRnHF16d?qS3uhj?3I$F zD=*^p0Knh`NW4CMb2y>_s?T*|W}eV-);iY#^9OYp%VbdCvjM|G5%?+MBgl`eNpu20 z*>8-vE-(WS>;fVpH2p)Lq;8IsSth{|%ei+|LLun$h?)>ieb%FKf_vbUF+f#Nh$&>q zzi@M_gCUg(5NUA4LWTX#2oF5SCavg>K5Jz4yN#az(E{|_PVYBnUl+LBlLA|iA_^n! zQ*kFd+8cu|N#{;u6k7(Untng|gz4=)ntM(= zoNz>s^!j!G;$r?fFmJ# z!_djyg3hk4z=t@O$lat1$wwD$LL_5NnV9XND} zrXYC9=|zF&-o#6`U44%V&A|P@VJ=UdyeW=rj%JV7zp-AKd*9_0+V65V-g-3Z2C#a- z?q2k7c@LWKx;lLm69SO;Q_|4P`K2b!0EjiRu(*1|Q|2}qIk`cZ*|Rids0E&^ME&tE z@MN)gKKDu{ao3SowS9WVzC^Z3n&3uqWkJj6No|{cn ztH1NnKx_^N&Cr(+OEP&4nfu&*gOB#x&~Uu(krKq)7+i9>%WuM+7Nw%B{2m4a?xINx zk>TN9FdSuIX1)ll+*gg`Dy`v_cPV9M*FgA6xJ)kF+S>ZBOL)yU=zi)g+E2KkO(-0F zlsRZ(y|@0d_x3F>?@3Ep0;GH!$wC3_LtMpSv@bRkEJ(#>m@a(xTR3 ziggo(8d+Q8jqBV4RlF|(u3qkU+Cy@_Rr z1I{QJKRdoYoPPd*xZ(!h=hqr}SL5!QODZT3tyXU;E}>C%b+d4QY;U{3Ef6`6g8+ib zB)V+S8B0H+S7s7gZGnZfwY8Dn@RX#4JGZbgxP+VUdAf^qa6ECbH|tN)$*RK!ATkkc|oqQf9 z9DVfgAuk^vBMK+vrh>eD{qpw5pl^B}FJhnkXpoeVbQo8B;rPx!=srXJa&e>ezP!X_ z!?EW^aAf3%y5rHh7MMl(fH130d~){R=h|9YAog28SB70RzPfAY+dQ8vA(8atBqA=(9|7!pBSW*or zU^ra)mIE5cseiX-7fGZ1$u9od+bdtfBYeY8E&b>->32z)#tOrSFR!CmP&oK+t{W39 zZNhvGTbcdVx@v(=AYi?zkVmxmZDN!~zXL!{az*^)-zPA`!tNq&e^S9XeR6$>KEs?> z@Is@c3`0X-Lz6+{ja`yHtpO7O&?~t^Pd5hKr?0Q?`k^qlcBL0`4q-3KZU35jA`>1K z6w!~G=O0s;Ks*~m!eSc!5I0qcVuHoY-1&6j=+y11q=9chKr_(Yo>984RFD_X3566F z6p)CY?sxxN);*<$NZvWz#P&PH^*i5fQt~nAs~)EpvZVxH>3&@Jpu?AH3gvAwfRoC59laH;uqq%gr5%(}WJ z-M{aI;cy9(E=7cBC0ZUB7;!_2ydy%)m+OKn)%sa)v;1Y1~WH( zXZpK!+6|oy=Fe+-443EtcI-`)xcRoyxzT+4_RZDpWNV9G$6@};5e%mrV5WC`aunA9 zuGYZNDw(OAMSA55GYZH17Fdt1>tCX~uA<@>=AI7eb5|R!QdD!ky<5>h76X6v0ne6W z&E%x@zZvNx=$M*$K%O70p5Bga;QRhTkT>a+nB+zvSdf?`3ZKVA>?sTUp?{3Wwk0hk zH3iHx68wPq@$yucckQ-zc4m@J_mlp`O&;NZ|G_eyV>;gi1O(tYi7VZE$-tEMk|8x% zU(^kcb~F|8$pzX&ewtYi?FBe`d%b5-Wr>eE(0=KQ&sQJ=pFMjfk){kO9tb^qU_|~M zEEnj%dGmd(yDkytZ;%ATM=)CGs0~$V0}dqT`oB#I=Ui%gjif*aEirk21EwUtKxdzOBJ%G7Qj<@P zva;BYPIl{BpSW(27nhYC9`C!|y?gh=zkmOrI{1ny=95cubFk_{biM9GuM-e3+bSmb zIPJ(uOoo8*f{$ON(y&Jm!1SZxF;9&bbOz$|bX(9ZtRsnYZ`bYA?$RarYa8~pxaBCc zY!XNdNke(ShYSBQvQEeDocgd55P67cQ%ue#pP|YHJp?@r znCizBI=WAAvidxXRL+0=`0?n(IjX}O(CACx`iJY>PKlCaP$D9nbFqZURxCsK41^44 z-q1PwRc~iZtoL?XH%&_3dgTh#mR*ui@z<|kPr=`t&`?%)Y|g1&IRIO!kvCjn%L-jc z&+u^h6p0yt73Cl522go=e=(_5t#;!I6EpMv@qSoX z*d83y(>}Ly~}dm5xbBIqO+w zW@bIIT|Tsqcn?#0*VZU$X}`OjEV|8zpUjH$-n(~iadO$FqGxn;dH0gkTwHvHC#M%; z^!CO}8D1Z!6K{Ch7V?0(03o$`&q~$%LeYNBkK7#iFRFd!Nx?05 z3x5BgU}zTFlNRU<)&YV{!NeAhnYlXE4lTFf(mA^?EWAOc|Hvc7c3y^eNc+8i(nT(L zQ}-SNlR8wm=#>#jNBbV;d-nBb?z(PAdaMqADNOCUH_sGkP#K`LK0e#n-AOk(q=I^2 z<4)OBV696~-MkEUVSdHH^!qD%<-CYR@9m{G_M%^PMJ}%oL4$Ge=!R4h(mo>TcCX8> z))Pnyh@PUNqTyN>WcJ$A)8h^=TvzAmyTG#eKMqnjomg{zS)yi%5=~BX25Ybnh&>zJ zp{cyEbwkRwy}i8wVE~cx0M%mqaFdmVW&H<7!QNX3_RF0lgbZw#VIMxGZF2QqUShd0 zi|&O2vPzd4{8Ux-141s@!-=GCM!h$Ct$o`_=Bi(Zw}BUgUO8-eQ=Wbx-TL|Z>)E&D z6mOu!0*|buqT=baT7er95|Ye#xmRJzD>&TOJNUI>dYIbNwvZtq!o`Rk_c|X)D@syQ z7mxw@z`(#1998mum~#1spRa{`Jge9La*i&uH68neqGbJ^^S^oSHZ5CU+`8ddgA5KJ z2zonx{rno5NW=pG7JP=m2b$)l20g^0A5`ym)m`d86GvH5I9yM8^W)$Iq=!Z)ohijZ zXjs_4!2;JSlcy)ULW3-!mxZ3-`8iLsvWBL`5Yuuq3O1AnC(`B0S^%6~|69~O12r85 z#Dr8UL-I26GBO+}tlmH?h3zJ>k@syaIns~5I9SE_Oy42FJrV_!tOk<6Tb!KDz?yu6 zS}Cuf;1?t%l_Uv%bX9W0n_M!Ki!j5h@N&R1%S}ecZ)i*(SmV}Hu%1Q5{MEB+Hf~3E z3CD9uMr!LaK-0^YFDL7dL0;Mb(Dk|l^%QsaZ}bu+KS@Km#Z6)1xIOjPj zrK1*}svRvNQePyxz=0PUpFCmGr4{7V7M9L<%KyonKuyyXdwG9%I)2Gx$Xs`wubTGS z-)nK$!K<^t6rDdIPS*Pv6!d*j{M4Zu6iEQLpXMOVU$XvXZ!RI8YZt+bC-+Ji+egfX zxSMki$ex*;C=p*6l_CF`cRKm#g!~Hs_h(Bpg`Wep3Cy*wqQ5=<64?1(gYGb^+e*uV zB`%npoct9|JAqiaVV>Zx0JqeZwN27lUO%ExC|oF2tbaGn zd#S_n+70Ot$ns+UlI*7wsl1)uP*9p24ZEcT1$f_m$A-4_Y>28_wFt~wL;J2VpoGcrB^AC(SsLJ%qxXC~>X zD-P%ktJ&1&#p^MIWe?N%)dYVV9sy)YjMcpm@Iu^%jxY*~Er8 z#{5}&b3ReI9x<;EnyKf{!>T5(&CSp6`PZWjm#=upfKxzsUD5U;*Dk!=#hUee@IL#4 zZKL{*2M@w8(HQ>^9xN(eS6V2YJITD5JLwKgtM?G!Wu14zIc}p5FK0V6vfoYw-TiM=^of*tz23f78%Qv$CL6l)ju)-T9T zFxQcg{vM_|W|Zh#))+U|n%6BnvJ}e1xj zlz!Ibw4x=wT$VY~4O-)x~DbvUY#KlWa=M!5Y^lM1zhs z2Srb}`I~vip4@xib@@-OCCnH16+VTgoVbRjz{$IJG|yx>OAu%1fP;P4+daZ+vNmdE z{+H}W?q>|sBO_V-dzCV@fymt-Pwd9R(-I>Ycd-7kpE#Z`j~{2b-@OuFbvo>9so=WSej^S3slF{`w2Ya6ko}RP6+sF4Ko90Y*GE{oisvgAOtC1-@ z8Ms$B`fBLkSGeNVC(y2xlkE_y{FTb3Ht9lB=sgH245CE@`jHxT_}{*$93KNOAkyF8 zj}@Cbzl2R<6&=aQX0$BW_H{8$R_9V2?CvuY$c4r}#jO7nV>>H}&>gq=JNq#GrE`l8 z^uOo4-6pH5|LoJew&eF!=eLIKcYnYPTC@h?>7tM);;Kt%#%9%_XNj+6V;5~xzWKG2 zUqnj!WXIx7a+jCjw7_FvaT_9clXO+m-{U&k|pOG|6=Qn z!j}J3Z~nLfkK65KCdrl(8p`C~zsN=CSzY+Ufx z9+|dl*RMapiZWc@u}XCb4+V%~3en29vPP*QPBF3v&s=_svrCxy$_sFmja1AOAxvoZ zda=&5V9G44*8DlywE5(#MUMS2@52|(;1Z(Z71kdvxr8?kyI5AX$se`jwZtNVpr;*` zi6!T?UdPa`VWYpW+z-&DIt?zWWl*>PUbF2)@#(MWmdg0AS57V7yLWGPkEsCp61t(v z9sNAvUv@!0_PwJ83!=nG6i|%KjRc92_IKz9A*s4Jj0bPfk2i3AIr(V8?KU~paB-W~ z^;h^r>_6^diRx?m-!UuN+qcK|ZQ@&)tVk>r_9mr1aOt~>pL+G&)tiql7Hvx=dt-hb z7b#Lhzi_t$ng^2Q0$UvS?3p1g(eMfG^;HLn+@g)I$5Q%Obe_5W&U|u!+#elNM@Q-5 z2VX^jQZgStytFFGTubI4-Fu9#S{1h8t1my!S#&&)H%?Ca;wA7MwY6O|1F<@Cv!VJ> zT`U{9l{mvX^7)5Y@5*Mi^n}itr{S4WE?iip%E;3|g}=YzHz4aja;mfEg3)JwzsFb3 z9Wqy&XU#7Jdqm4YUR)v^5ic(^qk=nl%BGYzWw=zYo<(r;I(}ml6U#U29VFRqLFWGm?M{5r4vt4iXpQRP zhO_1=F^oX4LhKSelx;0Lss?#Pq+~u@u$=5*;^|mhvM&yObL?@~f3<(rSoGLtz3P$% zmdfN@&ng{5rYdzMwjUQYLD5CVFEJI3V2&?dj6)rV^ZCqHQc}_rBKm9+&~9`)v%6ra zNR(qRuMXRySr^0cRhA~ROL|i}#TBj3NF0$G-`1ilV#g=);FkSKmo07JjPnD!VB-U^q3R zS=`|Kz!_4p>_8q~GiRgi+iOYlAYye8NG*bXkZO?4UCSyFwqTi#q!@6eYfZhKkj7%+ znaz^?x5M#F94|I%6(;bDjD*8w@zCnmSwH0KL@R)18tpW?TRI>K=`GDBF>9Yx%>eY^ z@7rFKkRBZHnJF)RZjIzl%Q+V>-!;l+QQ5Cw#PH zO(|1TQ@KT=bSSGr`4;1lFMB?CI^Z7jByCyOuSzM&tG`Un)x(w*TMrdMU;O4dtX@!XQ@AuM*4aHX&v+SjZzS(Kr6IDn1`Gha*u$%rBBrf@2 zw8ks7gh#N)p4P9SzvG48>sPN1D6byW5|d2gD%>3deC2>Toz`-n^$_E5FQ!80BvjLHvPtBJQ2E$67A_dB{2fSu2NGH& z5j&No+9>1FAd?8QPG$H6M%&>gFWL8pp-WpH+|dz7wg<(s*dF=+wI1Tfc1!~JMii|3z5ZVDi(AHvkF%aG54GMACck0BQUwKt zYzJd+Nb1s6i6+F*EB;Z9C zi>g6&BY{smjZb8RpYgy-OFUCoioU26RMmJALu-sFuEj&%4IrIQXiO=&2ocKeK2R@Bze z!1obfd~1Kei%iB6k*MA%7$ScBd$z7(6Nme!RGi9vbVYa; z%)Oex9)!B}rS>_qgWsfXEkUL)IXSrtq6%M_GfyO(Xo-EQnzaj1 z;McWNVlWwUWsb>_I*jBe3qF5#^q(lOtwUp_BFF*9$Hyb%siyBj&pOMcb1zBsjEahi zOn^xXi8Q>1I?wL+hcfEWS}+9VZ?vP;qU6)y5+%D4TvHA3bj#5b4*USs!9fao+c?mr zw8ZKq$rDst&S(;t~?t zVC=KcF8d$QPc2coD*3)u@+lSz+MhF}Y}!3E~ngtOY)zxDABDXCxeX z!fqnJd+**ol1+2EyBria6zt$pcpA>w+%|A=ktN70DvH&r!hf%~^m`fmyN~|W0_?f# z#EC{jYgNNLkv)9`GCCWXKwzKjvtKCzGr+0VNyE!Pa36-|4IkVvB#J92aTjvb%gT;I9L|Cc=SAS8?5+Pa5U zjALh`qr-@NLIh4P2Pfwf`{KxWzB}%fb0^k9u#cC+4I-&E>K$}Bl9!hc4i8^=ucYKj z&zLy!y{eaYcq`*vp)V8|){O^{pArxdK%-u6JViVDUPr68HagwyMuo`Vw~>6Wl=jlu z!-F_n)cEq?Kq9uVvDK!24#5RL$3KXYIpg$0ASNv9aHkdPJcW5JxaP*XyWl(kFcw6z z4iqkGskL#TAW7)*+;lcQJ(hq`Y`0F*?gBj<8&R|vWiRiD&&tXw(oD1{c>C#Y#vGE} zfd@K1~Bu`^5LzhM~^C?Zc{;BJr1fC zT4JbzU|cKe74bP6wrqKU#dXnJgc~lMP#>~0e@8b~7<{(Q$&;HAg#cxis_^*Q6(pNR%}!zQ#NpBLo;&aSS+NHjVrA=nO0O%-440TM<>u}+sEUa|rl0JSd#RL! z1cTpW8~Q#aUb+;Gc4p+S@O?#XL)lWyRydYW)9Tfau7O2`Ti^*(N3IoWO=5VYrK?aE?w+(ed4uN=iyNWktx5Wy8Eh zYS`P`Gv=FQJbem-e!za?|Jt!)WK}$qji2@zGdgJXjIoxN&GgqoSj$Q5$atQ3G_^2mJl5 zymQl1z*ttIzH5m{%?Ladu@XG%f?qo6!k;3g-TdJLTiVO;U%!0+TAI+vxH!FCyOyHv zLqScA*ls;@YeE^e2RlUs(5z*nM3L-J2@Q!-n~abp_o?b|Sv#-OO^$fE^&u;pF55?6eBbOi~kww+ebrPaJ2C#fxW7 zoFfr5Sf}M+^9{FexA+_Zw_$?BYvSe0aj?aZpW(a0XQOgKsmZKa!z&^szUPno062w( zP*x6wWG^Qxi{bU_*J`ohk=4;V@^t~#QCK6tWlIdol4*(l(};s2kin)YFn+?i|FxcG z+^~GZ~jPL0(?oGOsVueTHK2BJrfrR`Ht6 zw`?9qqbKFxo6W=gzOk{fq{bN%j&839XQ5F6%|tevarMfT3s;_FMVH;Gx)^?3?sck5 zC|xL(Q^TdA*0ZGc_q%}CfZ`_7Ftee-2(@(!A^EPwD*6g=@`Q!e)>3coFI|kgywb~&;J+HN2yoy!gr7=uDGHAAY_rh}xp-?R81sO_Y zk6tyueoN#tl#vnGUVdB~?WUu^M%c$ibB~{Vp75jVBUmMP%p#|L*eRob1_PRo0A({H zq9fKD?=rgsyS`=(J5&j93&ixc4K03NZh3RhX~cY{W44dbb`~}e-k)wAs1o0rB50^7 z>q0BFqJ4#tF)=-M%GBIV$U30oXW5sO{Rc|ha8LP~8&ZI5RVt@m7X3P@x?w{Y`mcdK zqPttem1~!=Lq%$~e}7DT{NgezIq8)vzvK9t^F6jnK#>XX`Tbof19uP2uLA zVoC9)#T$@r{JYnQ9OTI!Kc4$wr@Z=nbOen%F&mDaApOit3VyTt^XJ^oD=65ABUNM` zP3*`2y~>V_gA<>i)^T=o)BEd1mM@ROrqqo@VO_bAbtU08wY*<%7qulJA!r~H%VwrNK1H69OR}vt*@uGw#pC#LF#MQuauBv;|2YLgbcE+ zT6Cg@N>xG6*@Y0oYX=0(<=gDaGQVzWVG(K|dXkBim6dTxcsMk}vryp^r4k>ExtV}@ z!CM&_ncxP;YVf(f=CV8uA6i=l2owcap=co|2jUWiiT@n@K|$tv)Z_Q0$G_g1?HKI* zo|40aR)bhB6VBBDoP?%5?4dL9eUin(ixzX>im*d%Zqq0CzqLd>3{6Iy6yd(5HrkQhUH9<6Gf> zPvX`kHu^qpm(Z_()8?Taw+0^Mm$Rzc@9{Vc7s@ax6qZ3kQPG@ytK>sg@?pvz@ERf_ zB7J>*sZN!(}&93A;Iv&c_>VGUKKw%e23hD|5GOULR0+{|N zpCTjOKQuOSzUxv@ zn&b2*hoK@)g&eB{vunRMEPYg%!r*a?LZfK zEi9;=;zdBVm3YHM`=Wn8PC7Or!2vZct)(7f0QihXNv39Ir@>tkLlemt19KRu^G|a# z0qP_!LI&GMx zCvh#*D+DQDy~+&nMa$wGc)o7fBI+^Vjch4X7ILp7-(SR4f=m+K020rh^&FDFM4~M6 zK#uVG_)j;$3xrDbD4mAOVmQ~pbgrS6AdLCYzhMnER{-~$$P)mIpg3VSN-FZ3I4r8K zOQn8ZfE&Ui8;`{{G2z1D*Ek_y4A94wBavNHqYf3<{BAsj-mwQ(#M(fu1%d_`p3^7^ zS(O*$dt|>s_lSd$SjKojbMHn9yhRCH0>T^RA zlL&18!GkME>JNrOl1YI;;w{2`T2|Te?)6hHmgX{!Pyxox_x~PzZ#lmJVV1-Z(LZ_=T9!6wx;H6pQ9L z@CLP>3vu7@mY+X=Mou;gD{L44?|Eb7e)+_~^PtqVH8;D4U_TfV`dTS%bn%XSU zA%hqdkrey|Vsi$d5j25>R%0pNvl>?WW!NcTRwkk-JD@D+F|Zub9-b0aqWS=spL%-i z;HA~ohw_uX@BYR6i2ZvYSoT!C45+B%=$H$G!l#dL*R!{A`G25jua}pi29|4j;vzO0 zeMX2kBceKZ@aleV`@@H$J2@gEfq>H0Pb~xLp#}wM0#K8vs1k%}J3vtL$B%NvNg+`! z$#zG`T29p#bPe?1Qqa>yUc9&*aYq)eH9`lR6ovp5>x}vy?Ng_=V2avb9E9t0;X?gf zIF*lk*8Wd?$>(@lE>!HGvS2Y{2?DRcb)yDU2X_v~pvzk|Bqc=SGSD|7BowXj@bgE2 zDM24GGGqm2-<u5}c@fLc|B%Ji<=C>|beNkus5RLR5oa?5dX+;~HUrMp)aB zzK@Rzq;<_u_G0O1W7U`bhvm0_dt(=lFQSrAU^I~gSYj~AkurwZ6x?!Zed;;=9Btrh zc;``c>HdUL$(HBcZ{8&L`P#kg_RPF~ofSw6!WnHC8fl~IS68HPUHy9;)CKPu|=+|=CJnLv)N zib{>sT?w4tg(2Ele>Ux}O&JC#E&Vt0JL8B}4Wx?#a_rQr<`NnjqELRf-gDuFWXeui z5HxPh!K-IpHa2F$RR9&hriA05n42&0R=rG4uOx_==J)Sq{|%YMPj;PN#COcz5&A0> zpdAIthv0w_j41$D9V*=P4A_rgS2hJqE29`D6tRYL$vz0(j#f&Tr6Pqy58;@#@#~_# zT?`05kV%$=L>}-NCHOiBHXxVH%g@K>VBW?e#FMqCZy~){_N-l2TUSTd4(L-EiKQ(l z*!C}|);5I;Pg)f_jU*}`qCaw;57 zHhGpWm&I{oHo_SIo`$lDj!F5Lh)4$gJCS-?4MYu%HX*C=lms}z3Vr@8jYeG9U>9r* z>Lcn9T+=!`xsX%_c}eo;v`Cp?G|demoG-C+A6O-`DWD7YJn*`TWFttU17vp)X(D_% ziqhJ9_wU2_FCZk_qoSTMUtIEd6zuj*_$8k|uMI=@<%{+oLl@{&+V)qvP31d)C<^E* zv`;`nYV~S1STQW*nGW}Q1f~d(qwx`e&OB94ce9F%$>anC93en{(nfH8{4jR2wN7`V z{&Jc!Rlo{*1}uBw$O+&D1_r{xy1@yd`OHFTBY;Tr#{M#D zH+aC_YIXQHhDlt5@71Fxo1K+mQuVMmgwBFM0yLhTm)8yqJFo`w7!v=UI?7fPlX^7MmxcNQMGNq5IdFreoq=0$2C;)tFqVO@*Hr=d zp)`m@Kb@uu&*dvMMXZP+mxU zGSSBS+SUDcZTH-B<^f&A>Ut|W9HZoW7OP0ymJc@+B!&$IL zS9b68qFj)${~@N~%PZIzY;N;6Y0Ru8w2#amhKI4%QL(#WRR*7k)LQJYb(*jZ(7Da} zptsCv2>p$WSf!10?Cd0z1>+!aqaRt)-vnl&x-0^gOsg!&G#yX@6)4MzN(ss0k_I~u zkM%F?&H^LC&g49JKpY?#2UtRq56|HVTY5!qYYWsXJZ2PZ%ItW)rXCaweKO-bAcD|W znJfiv75d5d8QQG^RS6%9dKg(*BM7qUwjBM$6gbn?Ng`T8r^`@C79GvGqT;oW742C| zBbP5zerd`ov$7|+2{9*_X55S^+)6AGY}oG6$I9V7=L6|U}>`+Jrc%a z{)giC!fFi?^N8K`b5MM_q*6&Jk{G0*s zW(e5mHf^t z$A5m&uo#EQ;)n%=z#%25wNIaB-?_6SN!kt!1>TOC=|apae-cDYv5tsw1b{a~E@P=k z2vgdXD^DSZPaw)- z9gyG%pGmMn1P6jNSK}SC4oSosg+gZmS)G`nMDo!khTukUHm#i|m5=wJ^bidORN-4a{%WdFB(N_lb ze)O+VF@nGb!#1GjJ#O{Tn-%>MP|5;gt}*j36JTr%4HBYcoM1k@Sw8qA?6f|4IrmpE zkle&YF0@{RHG28byMM{Yz!|r1A0G=LA&CP8lK@E$zBqt`U1A-Ab;L%Wyv$Cb7T`O1 zEzAh$hIRLyn`kk!vf@BUOOHdv3Jq@pY}pu^uvcg71E&%dCO>{sP1M`R2h~z+$aE0j z1xpAjDCgfBx!+rvZ71?CqkfO^4zYv{?g#~e2-ekzTuLM?_7v`>DHwKx9RojX3T6-U zv5w4e?j(0IN51+?_B~Uw_$sGgYm-N0yAJ{e#k-3LowIxQyOOzZ{TwrIWpjC4F4zNn z7T8`agbuoi^sy*&L2PV}i--_s42^2Ci=e@j&dSYYqNicZQ*qZkH!!V3eHssq6X5WZ zhQx9JkiNk|UXc)%|3yaH$qSGO7!ewBk4Uf6#ti8v6AK?s|2|XTN$43NFc(2`4j+MB zY(OkhU+8pxbiB_@T3Q+`4^RQ!ASoxwqJR=*!LX)^wKyi;Aus@66B07gXJPS z5p}ESix-JDfuKm~4L~D;9I(TB204Q$veCp6;!DHGmtM+8?&{;j3SKPOJwl2Z#0wMB z0_j7T2C##Oa&b{jkXY&ZsQn%3Fv;wbWE*gtzzyMJk_r)sbpZ@ML7ij>$~7=gkPVt- zeDgAqIErg$g$O~=93&XU@7hZwNBnCRBKb%Ha8uB{8tGI;$Q1l4DhHYmPw|+Cg0uzD zA;zaBC=D5B3FIiymJ|1uoSUdwyd=pkLJfiv^96rMN+cLTSy1cQ*^xfHT`_&5Pas!| z*q0x$aA_6yF6nOwk25g=s9mH>1k z@WR`&36Z*PD47UgfUcc9F)S`(NgfenvmF^4aUdPYGZP}+TLd97RtK)Am)Kkq8ar@@ zUB&yuQ+K^o>7@S20+FLjc&tk|A*t*6S@|0x>|9h#QmHM3og>a_;mZXOutXt5{XYpq zj`q(nf?}L)`aR1<4zhs+Gdai)7vnB-5&7i0jcJ?!q9mJYWz`O&iVK>Z(@9O;k5c{Lj5M1ZW}LcakL4I*47q8tNuBgk-SaH!V-HWQIl z_GT=goHBY}v9#l`U*J)YKbNu_QXoQf%eMEG! zLRFB0NY@U{bI}5UiFgetWJd_Q?q0-?9k~ZjvN9DVX!rFz*k=5L4H6I&BcTVv&1b(^sVXE^>yrXn&wAZYjveMF!=gSy6N6kW%Uf1Y zFt>u(Ew++A3YGdh=#-D3@Y~~G17=$aQ@B5b?O~1-k7zWG^#9= z;1cp3akM9+)jvY;7%^HbRWz(Y4aQMncI7Z0EmDSj<5D4^0#@FYt=0>tuR+5CbbaCi z15%O_+>D+#jn1u1Hic=`3weezxcrp6Z zGA%sK9oz$&=g8-0iDZw+v{(#?$Es3-BdPe&O|gr^FMxcW^4Fk$l_d6f)8ffgUnz-ZSE2dXG!k@3y?7|qHej|HedaGW*@89_ec75d|3lgH6NcI++! zRr*ozHp7QDIruP8xYq)8k`YhPS$X3&uOaK3G|HJO$A(ALLwn`lIURZwts+E11sJmh z>T0)_*BvCToqUYSqJUB!V_-4*`j?dB%t;DjrKCzqO9#m$PBiQd=U85CuO!inV@NvX z(2v^~ISOPf9~oANWmNY1Y*<%c-)6l;8ohJC&+npdd2P>f9m-jxk8^=S$N*As1*YJw zI#z5JY~o_1a0|zhOX9DQK^kVE8*jtcA1-gMnXOfG2tgN`0cd2-H+{WJe=Jc<(W}VL z&o{tffoa}pWtFZUDBBQoI(f<9^IQwLtGEWbSTghb(ky&eT3} z;WG;cgS`d$JA_@Q7>MJ$-H@&9YtGUIk_`>#61xS;s(f3tGkTtqxn1O4yI8P~eP}D@ zH`G~a3tHwmM!bTT7?P9ygkL6o*2%jDI}|;aq5OLC^+!K+ajVy^eS-=hdWXu58{ZAz zk<^Fxj%k1epyHK-!MItXDEj%!m%9+>=*J7ombSV1?6n&qO{T!Il4D7!#{&klA~pcj z--&sEV1bmq`%KHXu^kCQuMo^Nv-5$W*@UA_Sqn^c3%tIFW}p=oVi!h7bgT%wOrE;^ z0W1QA;>m|&wddNOJtI9r@vYaPbHc|7AwpZdZe2+^2ZbUWrgxAcP9f{|ch7L9E$Mp} z_6X|8@@*7K)lmTnreMn0ls}mn2aW0~Bf$-alR?|N-de4UV@y9!0|R%+#tDbPTrs@E zm|grfP_?Xvh7Azrg%@A$l;1q-g;6`00aj0cLSZ~1lMx18f-;6}%q1I#oa%`Se2SzE z7Q7<43ROpO__!Sr8mM~roh4&=ARk*JE88%fa8J zR|83IMlBXH5ew#ws2KUkYc>v%sRShQ=5`+wOs+3$6ox^3V6dL{O?N z$VNp+TcES%e;f7r0!pDs!(RG+Dq}xGAD|i^ec4Ts_Cu@V8dMBB`xpg$M?p|OSQ7fx z$tk|ZL7_&1A-oRrbgZ|L)QX)?Pj~e(>b#bnT|K-6$5#y>M&-sXk$!$CRs$k_wSY@4 z6A+{P#q=deaY#RL`uD2k#WHF!kwGQLkC!YK-jo?QH|+wuFHthO-Oerx6gu4i)Wbt- zF%1q3n4=RiG$iLQUAiHm8{TT2Bu!=|JVcu;x&iQo0q_h4b%Vok?am!@6ibl_l5QpF zh)zH0!^8Ir;eb3ju`I&55N08(OMV+L4_RaWaY54TA4(;ezItW~#kM|MkH(K(yyZclnlp|P1`|Cxsn_!p- zmgw?C@4?lW*9-FppLh+tUT~q|2b^x7k0%WtKYq;6FGivKf@`FlmB#GGK8W>+tALF< zpOWG_$7Y<&-L8 z{5pDv(|1dkOFb8vme&DyGGRfo2(GAF2Qz>vv-)HdBO2D}#|f@TsBe8-3kB-qnc;G@ zU0i0#N}PStsM-=fgP22zYGBs8e^x7jL_zO9F4Hhvc@}JbW)qNr1t#p0cJ5Wd z41$V|h8b;vXuOI;&1rQMKjwj*3hu-#@beiNw*kbVUfvFrU+Q)jQ-?5=d|{RKn8FaH-1D<{zNy2&23=JbMd!-ez~+j1nx1Nlr*`qPg)aD7tbGF9)s@ z*u8uA2MZA_>q=ZJ%G&M;zvBQX#67?d!9AR98%mKTlMRu@D|rBrHM)y@fAl3h#n~lOPk0bUP*PVV$+e6!i87Y*+IC&tBKC)gE zO0X{A0RFow3ugd-x=ir}_~R*qg~Fdrd^n2uBOHy5$DhS|m|%@R5&!?M|9@oZo)ct; zUH^t!@ONcLduH7&fd(yYPF^($I)NDsfj`$95%4AU`P8v}JA*?27qbl@gPoct`e zc6D{l_I1O!H!qBRH&oiKU;D182!eG>p*!q z0Kw+{drdH*14wz^yVo>`*EJI7P=p`BV+89e==6DF-ZU=l)*U-`o0}&gynTDyR9=&4mptIHWAgIZphJ2U;UYlAJ)id8ot9= zjc83lVeIKoNtme56+$hYF@wLq!IzY;ePOL>a5Xo#{g*p(4Knb-au;3q-#d+TL zi`huxo@EmbK!*J~1n!u`S&*Acg&hUV*n@gfh$Mi`ubSoP%M#3+H2Vo7-J6>;QCf@2 z9B@Ee;g3#SIA{pSyK+bRHSil){O~V6IcUWTGz`CFhMWj=r{ClnxG~=ug_1|mkd$PJJ%9Of;nAL_fR-Q0*Z!EolM=W{9uXa7ERild z%!xC5N#5>E=Ma*n2I8~P01o(iVC!w?RvH6an?Gw89w0M$;EAr|#lWHP|fUx|JQ&=LdX z=wa68Je0j~3U4w66?uF3@lPAljvn3fP4C?A3$k=dv zz{2>l>Mqo`6_Iht;Ma+p0rov{!Dl}(+$GJRiae8yTPU|Ff1ywq^n0ER$>?pom@_#! zDKt_?4|ay`LtI9ByQ5je5rkKEK2PTKaGr7QR6fRFyD`jl0Kh=icT_xQgPpjl>OKO( z?zy~HwyS13sn#7ZB`78q)DwOIP4lC8S6QI%JB&<0PEO76_b#pOxwvXK_`{K(h7+_`h_D$*#l>7aj`#AwK;hDpz zz4W5xRa0OyG*ZdgGF(pie9lO*kbNP=jRB}9ml)fA9^Z#xwh;Isyu)G**jvT% zMx~}}IGkj>20h|4N+R4(p>_Fg)LN95CujDz+|D5LA^=eauv)J_K0c*uKb_6%p48rm zy@7=1Dk7G-siq*(_qt<616B&<3T9aFO>UJl8Xk?;@|w`cWMX98E;DSs(Jw0; zFjP_%AZ%*0-r9`H9Q2Z#P5}p~feLV4LN)3$pOIXxu0AI=B**yf=mV>LP#BRu=s3d7 z!(Of^@G1n6j>gmP|7xQy3vAYCF7q%ZZz$nFp~69d|G7My^3{vsW&eV~;Qv-Ht!r z--j(8N0ZP!V0`0S&7QOw?bz`SQ3PR7@I8AgSYD#8144#gpK^pWLmlO%@RoJaONqBc z(Z+57{jB?^yT*LSTOATyhCY-)yLYEtct1ImXc_Su_nAypd9Absfb}YLq5CYXyNEr& z*w0}_;kuKR)jVr)J7pb*_KN>^ zBOLDMDL*F9O6ZPrp`kmdCv)MLPpZOx87Ua2Ag8H{j8|@%dy#5`s9k=L#L}r4i8E6!Bk zqKr$0zJzm^VN%a{J@Q0(+6`n5;db}mH(xImT6*Eim0NiJl(cKMXthv)$u@(~FNPml zBCiwK*3G|}G56|K7YNzfwI4F$HbMe8hz>XIrtzg-U$&}$e~l17(W zv{rYEcCT)HsVwq4NjwjJ^C+fvpRm&X=)&pA$;{2n(+S^E*% z`vn?v3Q2^O1oj|Q(u%p4sR|)9nGl4$=(1;m_QW=K97hU3xaj9>Ck1xiP>H{Aw;^ZH z%3p}?`S%p-zg{Td{8lPl(iJlgP^LikNsJZB?Yzz3f*LN(5&Qeu2b_4p0a zSPm?6XxDu=frp5|H^6Ldo4JWc14#m{GMSc+MyA_lRI1@eP$~uNj}SYO{N6S(RojQ& z*9nz^_`N0oY9~RPftlTSBKpWH%+f}G>7k*al-PHvOW_xKU+Dm7is@fjq_Jqq_*X}Q0$_{} z&H-X$u-5>vrpiBW0b^4pJd(l7fEOh>8z7xHG0l&!mh%Dv(SZ1LJ_#~($7u;TP5&IZ zjdlWiU$wxD5%5A<%fC7l&R7SW@ToRxUxohzjE`}6SP2Bz5%ha*8YPRaWeF(sYrYfF zU2x;ZIH5G*f+UXG9p3`!9GS|4i{se9H50<6aSb?3sN$K4p<&Ut_+thJ5hsQ|5LEDD zQi2@?%sIqML&YVi?su<$9&mt6y4u+kp*G&En-V*{)!fW1kxX8O`m-@ur^KyM&C6!53qv`GW~0^!9@5Ms+L z7Oiq{n3lhbGruj5MHsXpkwD;)bbIAyhLDrDe&}rkb`2dWU!%8^ooZyP@Md%T1*BQu z%iRFjDt^z6q}i;vi}_3FYW2GiO(pw~3Aa0ze;ZN8-`oKXQ~#lJw<<3nmf8z3$nZ1I`0-u{5okFPGW@qpReSQjmhx;9))Jpwy9Ub6n#ez z0EF(dSe_2QufKA8>Vbjfs$iaNe^0kee?Dij_U3a9guNdy905U@!ws>V{XVH3-*fQd z>nmsPK&kC`Bg3>9Z7S!`OGDwUfxrKwEVByely-KvBf|xx`JpnXvRgyP2>II;`wLnp zI?ycREav*n8$;xhH_gh7P@m)sfZB~Gl;B-;ea2o^@FN-I2NeVHLp$d}qfx#)0P}G5 z`d0^QIsO6%LC4AC;Im&<&JR}J$jzxNP&W;- z-SbfIfEH4U8?u#7eA`oLse?ABZ*f96#C9fq^c!3UvwUel>J5}+`;Oz6k{Zfw`EAd_}+HN)Es^z^14m*!!{ z4(ul+A#XylfXQwpwr;nvb-7OdzlCvV_{z zHuBHo-;pWLVQ)j@p?#VIM7`ZTsV{e_(T2kxL@-HLUf0lhO9s2StsWdXGI*lgI6#Fs z8N70*=ZxtI#DM$V^)XYCMhi62BLPTv4;k+WDHBK9*VD5Th`@=#2ydI2`4BIpvIA+9 z@B~YwLx7FmkWauI@|~wL_Kl_AdJS!Z3qWspn;5M6$RU*)J!9iIR5Ga73_%_WUfIr0 z&r^`mE>!@549FqQ($0s+kF;vc(D@M$WrKx7IQG#!O0OTe|!A&kf-j>xPGi<6F}{w2%NgFE3tkD~l4=)gGCV z@V0kv-XI!nuRg4k(DYU5c-EJZ%Nvw@K0%o~R20BnaT^Rc85mnLG0Sz|C}_i$HghNjf2Ij~p&EsE{$WM@c(yF4&OUO}O_XPMg+v)p{p+~r zwtu@N2)8$91m^ue#?8CKiGYA_HATxO3k%1x!i${;SAA0LokSV1ec8G-o%BbLznkTb z>~YxnP`TSJM}FxbrGBGn#{1%w84`_AeX@IO`EJJ8FJlFFO zhq-1={;?27CvKLSP}+Jw)Lhk?%uHp&ZwR`#wY0Q08nt|@i0URsB|M{vRbSlI*_own zZeg6fUm~LGY5(pcz2$a}uO~bY_KtjLX*vbi((M-Am~K#GjQmUY&k%Oc-vR-TVUI^r zg{~)!4Kf8esWRB=iF5Gko8*GOTxPlCL*s0~j34cY)4uTcoX$0Iw94C>89q6kalkHCS_UmprO#k!jkhr;~$|#p*lU;UU;Y-tU z0L7R!tZu|EwFw5q9X+D23AGeIj#79$10`v!GY)hL`Ix>3s9VZfX6bdzs(#$K=(a;_ zVEiIZLC0$%I_K(#8Jkr=BZhxiv1--+KWnvNTCnFG)Uq5U7+?5(unFnq_7Mk?l12r= zkMhgBs8xG!&B!gUzrX;1uI_v)+T>*e>Q}bGeXpgw^|wZnIIF1U`1VeuMs-^h^fl`V zXKrZNmFF5N&K=I0W7~?F?lqe?zrW4?&C{uO$DwO;WfA3Q8iEi<=8TU^OPmJLnyA9cM-PCw;^&3$o`D2&m z;n~^OJlL#s`@+s!4(M&|Cs8vLr!nZ(8}I;PAmh1rQr_gN!5(rXDzDr2%`v zs9rZ~#Q1Rp5RKK*I`!aswyReYnGIU>>bjjeb;{V<7K5ISpxaS+o0KwEE0R{O*#Zth z_pZ~+JJ&8XbMx}%j0B9F${QBEqJC;)S3$w%I;`0}lxge?5SU6&n{!{grzrR`X5aE(V_&*HvqSN|?~QAi}EG05HN<)y1Q z8fgOyCMCJU6ESZPKqhsd=Tzs+6~ZBy=}lr*=vxc~IyC)&QGZe4QBc=|WA$Px#}mm2 zH6%zX+aMTfANT12q5TH>ZsQ3Cac>Y!gtyn6>o+kr;pKX(<$PZbp=1VzyX-5r*VD>7 zbcr(*<6^)nZm+$0~5_;6U&*#~)>qM~LCu_R@Wk80q0KfbxrT(n5&b;LzH$6;iv@=VToC`7)OyFT9t@%E#WKfF5weqOh&49uIsJd$@1 z5OI`t0_kFp4?avG>UEPIw_MjbB=L z0A=fKU;@F06+&lE<`qNNR~t8?FFjv`%u+;M9p9}u?};zzg#4y||*1cc62E;PS+@TX+K0Ph8)87pD?LJdqU4(A*#nVg4I0UT^*)TLY#kpq9Y_e0^x-G z0W~cPjoTd!lpHRoSY#%%ujKG9(}Y8Md!neo2-9eZwEgE@9L;rBWzBa+!a*ruwXdg9 zx(|RRRz3MW7ouCPrwL+Wqc1Z-MhGZ0UD{73L87yGNqMZs`-*^aWE|aHexYQ<46z@I zm_25LQ1mj5fgE3aY=fp>XOJAgi-BY19fC+mJdGDQVieSEk7Jp)?A+81gkrW>sa?pU z9}MtQ6Rm98kLjq=+zXdCaffGN{P5X~JB+^^K(Y*c`=;Ds;^R|FxCCuI%IHCa=|-(; z_Gs#KJ3({4by(3I0o}F_cMm0W91JaieD?)^T{-M)Yx_9SE8E?`fZ$w{NiACuRqtna zWY;Ho!@LCGk`pNtcwal8tVihkjidg-`sq5i&I)T#LMJZpq#(OKK}HoZ^lt$@Jud0S zqRCV(KUuFiZw5hOX*ow#5w`R(dK9PpgfkiO%3`Qm0!s27oVd=Xi^@UcAUY;mY`NZ> z8G}t}u?BlP4npDy}uOrV+24dCQqbN3q{xj>n%j@dVnh-58V zDP6?@W*XlFnb-$(X(({r!g5-^(OUE3!tXnH4wS^l#|L+IKMIuKyT$KC`SupVF_lh# zrEmPDWjNLt8SmKej_EWhS0l6PC5j)Oyw(P@v|@&N5{)^}(SP8_97_OGH4FWRFlr=l z{TxSY_g_wkF)(81!~4=d!HIg$&rSu4v1@%sfyX-x_F^ZfVAy=E*{)qz!B7m~Vx73) zwG&h)p*Xg?sq-~J!7z?eLBjX24;(#m@57um>8wkTmh9Y6DrTXfJ;nfOm zS3H0Ih*DvOBr-L@0-5f9(o*}`|JL1^e>HW4VK@}qB5qI=@hBKss;B`36+s{tS-c?2 z0hbntNcD&;!6gucHYsorJz@)lXa$wn8WBWLECK=rkqU|nHL__y7QqmeMS)Wd*z}#t zvHwGx-!gYHckZ3ZEbsSx-xU4P0T2Pujw`nN#khgaa@(cw@fahvHKHU%7HTHe)sN}c zLluJdN-#5oZZRyQRyg}WmM7hQVh&=5v{VjP7ZC0ZmKCDq7LGHt3=x{64dXMAxbRqW z4aImotzE$KPF6aG2Nk!VdXtU=vr}vKnh2WZ_tdTcFajpnAMusSqMygv0B9AeC%Ov2 zR1op{)T&*tEvD-m>$v4%bws4!R@j=!lEpp8H{=QeP!d9}&*Ca1*m0SsWf){(j4&r) zgWDZTF(PFc2GOvHzU@OWmxD=U93@H_9NS7D>&`N;x;Z4OmX?=)joFuo*+g%rv1{#e z^lUt!Cx*T0Ph9!918GGsi4zAfcq@>_LDYQ>H!}!0z zBpw45lT3zK%(uaS(8oVgujh)~7>*u;5Q=KHg`;PBev>v7y3mJbuv5!`!n$y6;QmEW zNHGis1-oe#2^ZnqM$EWAK=Y4Hjg#01kYN$~Ejh>NRuC4L1QP}?3(G`u%WXnQB3=Q` zTr7ZfT%fG%Nv?d9;7_(Opaf8^Jyy@GChH^D(5wV2P~i|s04^8J{d0-DNgx)?eVzUJ z5cL)d#xk5#116YcBe2zhF+@8{HHpdh0+!WN;ErkJUlY$&)(6Y?JUp|YqHIKWKNM+b zq_Bwl!8_nz!bv*}lOgE?Gp{3}zE2F|bf&J*&OwV@g5HTJG~rQE#14c1D!3;m;*IS4 z-m*w-<5#l~s%=SMk||czsGM~(A3#e8FSJ7&(%fmyleKMg^OhPpQFal{MQP8e8#WTY3)#rEjq2Dt(Yu^s+=b3Qh7hv% zedT4(;_sE34QViH=i6morMLV-_^Z(L*MADN>@TilFgp$aQ?l!Z`d`P)f%U}$A~ zQ%5=hZgE9?IcFA0V(#TD6pFGNZ1v*6NESe9xOr?2G*!kkJ1p)-1hYs&0`twwfX}M* zwMIur*_q~K4hn6R^bGVVoXPk~9YXpBcW z*5-rXM&+hCR-7EK?u$sYVzX<4WT$KMXi8XT?ml4-()W<;X`-i^0kcVVroqz~)^ouF zFHKbA?>Nfx^Q%mfzF~jWWL*73cHoaX9x^tiT5UB>k{L6Utms_s)Ef|j7MM_LK z@iclctJcX&?}PD1+zzwXH8bwKKtK8-Cp?C`=8@cj$+P*}VdFb9$>I@<;y6cgt-Z&e zBM<%4*Fd~^nzORr>2PYy;4ioNHUfG~QAs&%*6qFWL7PMCQ!XACZuRzlXvL9d_fnLR zr#<}+g4#@!UL5(h-l}^k&UTZtL&s zyPrAstMpS1y2%+X)dJBDxGFcza#3i^ps#Nhm$=EoDcbmtB#uA=mO-O0(x z$;J&vE4vd%Qt^Z-n*#D9G~NiQ;;+`j!GOU?&h@4$&A1sQj%>F2x1EOT@}@HOnmrJS zEyCIrYD(S6*5jJf{p9jvV`Y`J;>zTx>Ie22iKJ_fdx&~Y*6#KC%J;gfNqLm3w@Z=p H&ZK_;Db+pY literal 2574 zcmV+p3i0)cP)Q`Og{P|8RRXpj5bgrSmEzSMfBn+{{vpNxw?;5UX;iv9sYxy_`IQHs$i<61a_iv^L>h8s-`D(`e@|IgS*Fj zNGM876Gf;3D8*1UX9a%v>yJKD*QkCwW2AirU(L{qNA)JghmGItc;(H<$!ABY&gBy1vJIEUj-b8%el*o|VkG)LqNx#TG>Jvj^jIte!!+RY z)T4j$7+PoF1AkRBf}R#^T=-q|PaK1$c<4UH)Hpq3$4WA|xtr!ZQLC=*vNE>O6E9kp+5X0eKB$6>C(lPwI@3#oY zhS_%x7e|j!$yG?ECXmh~EH~^OeuK}+sWoJse3Z3?ha3n`MM9KvA?uqpEnBg4Q46)7 zM$p%a$@l;+O}vfvx%XjH`}a{(-HHth9!JaUwV0*VqGR48^gWNYN<&~7x)y$e!X>e` zZ5!6KZoxbKuV9XUDI%#M1~IVh?pNSdeb~6@$y`v|yk=XK+fHxnDqnUK4&=QRNyIVf zYbDM*cI>~qIy*a7=z7uqkw@agd(<=y-Q7L!ty_23SGdXmahO<;N=wB+j;lNm%=OHC zy zU|>La6h%92y4IPufI$9>Xu!@y`TaNgtg&41@PwMwBdmSm7)xAWDLoqjZ==P2#*k7! z3o1)cVSI3KP_!?d8G^Lg0FtLXC~JYdxi|c%h~lXEixY=%VSFF@!*3&&9>(Rb|iK54Cx5;s~PY5iaV1het%w`dgQFBAJ;aFK zImQC}(|QaCFYUm1JVfzSc)ebv=)ObI)0jwJb``}Zj9J0n0Xgn*Zc(rFM9$xh_makZbm-at_v5^SW zM1y1SW@%+FuIy*WR)i3A2N_q;(YO`O!A|Ts^%z}9ZepCj3ytlw#x%N_fNrKKtPh`< z|1{UqF`4LxHaCQ79+E=uUXCOZ35jAMRz%R%0(P!0FMv=sk>Nr8%+OzY^c-M9@+fz=G`qa@v4sF5u-2289-#$**LWnyNNDwDf1( zkUiMnw|y$tn>pQP=Vn!#|17L^5AGrjtBkN$D@v)Z7LXc5EFhLB4<;7Wehh)CMqX|W zqsiZaO^benJ_hwa&V0ub$-_HUk**?g6fm9|!@kguU6*zhK)$qn-<3*kFrYPIaqR=V zUaUvk>@F_89b@tHs8R!*QKY;INJ<2_U+K6Ca3e9Gsl2{qY0%a7J?uICWgHuLfj+MB z=GkAN1&ifT#2u}B+2S#~$5jA(Qn^;H%CCmIae4AE-Dsng|Hl*Ov!z72k3ZnJs{pp| z+pW`DDueC#mEWOf=ucJ!dTL}hzOeiS-i?m2E;`EKz4<&Lu~NnW?peqVU^@<+T3KKu z{yrI%Qy-Z%HEvLUz}n^~m?7x`xuCtNR#L2En!T>dQtIKdS#V-Hzt3RtwTeYtmQ&dR z6qXZvac*oc@BUYEH%@Ylv_1&tSjkbzzU6*h1(3^C`;1z;g_SmOtclS?KWk2VYE zM*oS<=C483XckW?GN|1jfh3Ro(h + + diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index 3c6231258..a8c58d58d 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -1,6 +1,8 @@ package org.openpilot.androidgcs; import java.io.IOException; +import java.util.Observable; +import java.util.Observer; import java.util.Set; import java.util.UUID; @@ -10,11 +12,15 @@ import android.bluetooth.BluetoothDevice; import android.bluetooth.BluetoothSocket; import android.content.Intent; import android.os.Bundle; +import android.os.Handler; import android.util.Log; +import android.widget.TextView; +import android.widget.ToggleButton; import org.openpilot.androidgcs.*; import org.openpilot.uavtalk.Telemetry; import org.openpilot.uavtalk.TelemetryMonitor; +import org.openpilot.uavtalk.UAVObject; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; @@ -26,9 +32,35 @@ public class ObjectBrowser extends Activity { private final int REQUEST_ENABLE_BT = 0; private UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); BluetoothAdapter mBluetoothAdapter; + BluetoothSocket socket; + boolean connected; UAVObjectManager objMngr; UAVTalk uavTalk; + final Handler uavobjHandler = new Handler(); + final Runnable updateText = new Runnable() { + public void run() { + ToggleButton button = (ToggleButton) findViewById(R.id.toggleButton1); + button.setChecked(!connected); + + Log.d(TAG,"HERE" + connected); + + TextView text = (TextView) findViewById(R.id.textView1); + + UAVObject obj1 = objMngr.getObject("SystemStats"); + UAVObject obj2 = objMngr.getObject("AttitudeRaw"); + UAVObject obj3 = objMngr.getObject("AttitudeActual"); + UAVObject obj4 = objMngr.getObject("SystemAlarms"); + + if(obj1 == null || obj2 == null || obj3 == null || obj4 == null) + return; + + Log.d(TAG,"And here"); + text.setText(obj1.toString() + "\n" + obj2.toString() + "\n" + obj3.toString() + "\n" + obj4.toString() ); + + } + }; + /** Called when the activity is first created. */ @Override public void onCreate(Bundle savedInstanceState) { @@ -36,11 +68,16 @@ public class ObjectBrowser extends Activity { setContentView(R.layout.main); Log.d(TAG, "Launching Object Browser"); + + connected = false; + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); if (mBluetoothAdapter == null) { // Device does not support Bluetooth - Log.d(TAG, "Device does not support Bluetooth"); + Log.e(TAG, "Device does not support Bluetooth"); return; } @@ -50,16 +87,49 @@ public class ObjectBrowser extends Activity { } else { queryDevices(); } + + + UAVObject obj = objMngr.getObject("SystemStats"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }); + obj = objMngr.getObject("AttitudeRaw"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }); + obj = objMngr.getObject("AttitudeActual"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }); + obj = objMngr.getObject("SystemAlarms"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }); + + } @Override public void onActivityResult(int requestCode, int resultCode, Intent data) { if(requestCode == REQUEST_ENABLE_BT && resultCode == RESULT_OK) { - Log.d(TAG, "Bluetooth started succesfully"); + //Log.d(TAG, "Bluetooth started succesfully"); queryDevices(); } - if(requestCode == REQUEST_ENABLE_BT && resultCode != RESULT_OK) - Log.d(TAG, "Bluetooth could not be started"); + if(requestCode == REQUEST_ENABLE_BT && resultCode != RESULT_OK) { + //Log.d(TAG, "Bluetooth could not be started"); + } } @@ -84,12 +154,13 @@ public class ObjectBrowser extends Activity { private void openTelmetryBluetooth(BluetoothDevice device) { Log.d(TAG, "Opening conncetion to " + device.getName()); - BluetoothSocket socket = null; + socket = null; + connected = false; try { socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); } catch (IOException e) { Log.e(TAG,"Unable to create Rfcomm socket"); - e.printStackTrace(); + //e.printStackTrace(); } mBluetoothAdapter.cancelDiscovery(); @@ -102,20 +173,19 @@ public class ObjectBrowser extends Activity { try { socket.close(); } catch (IOException e2) { - Log.e(TAG, "unable to close() socket during connection failure", e2); + //Log.e(TAG, "unable to close() socket during connection failure", e2); } return; } - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); - + connected = true; + try { uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); } catch (IOException e) { Log.e(TAG,"Error starting UAVTalk"); // TODO Auto-generated catch block - e.printStackTrace(); + //e.printStackTrace(); return; } From 8dc6b09b961d3a90f13aab07b7b2ccc6891e8a77 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 16 Mar 2011 15:19:18 -0500 Subject: [PATCH 225/543] Make it easy to enable or disable logging in separate modules --- .../src/org/openpilot/uavtalk/Telemetry.java | 30 +- .../openpilot/uavtalk/TelemetryMonitor.java | 41 +- .../src/org/openpilot/uavtalk/UAVObject.java | 12 + .../org/openpilot/uavtalk/UAVObjectField.java | 2 +- .../src/org/openpilot/uavtalk/UAVTalk.java | 593 ++++++++---------- 5 files changed, 324 insertions(+), 354 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index b403f85e3..c754c8329 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -17,7 +17,10 @@ import android.util.Log; public class Telemetry { private final String TAG = "Telemetry"; - + public static int LOGLEVEL = 0; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + public class TelemetryStats { public int txBytes; public int rxBytes; @@ -227,7 +230,7 @@ public class Telemetry { } if ( (eventMask&EV_UPDATE_REQ) != 0) { - obj.addUpdatedObserver(new Observer() { + obj.addUpdateRequestedObserver(new Observer() { public void update(Observable observable, Object data) { updateRequested( (UAVObject) data); } @@ -293,10 +296,11 @@ public class Telemetry { */ private synchronized void transactionCompleted(UAVObject obj) { + if (DEBUG) Log.d(TAG,"UAVTalk transactionCompleted"); // Check if there is a pending transaction and the objects match if ( transPending && transInfo.obj.getObjID() == obj.getObjID() ) { - Log.d(TAG,"Telemetry: transaction completed for " + obj.getName()); + if (DEBUG) Log.d(TAG,"Telemetry: transaction completed for " + obj.getName()); // Complete transaction transTimer.cancel(); transPending = false; @@ -315,7 +319,7 @@ public class Telemetry { */ private synchronized void transactionTimeout() { - Log.d(TAG,"Telemetry: transaction timeout."); + if (DEBUG) Log.d(TAG,"Telemetry: transaction timeout."); transTimer.cancel(); // Proceed only if there is a pending transaction if ( transPending ) @@ -348,7 +352,7 @@ public class Telemetry { { if (transPending) { - Log.d(TAG, "Process Object transaction for " + transInfo.obj.getName()); + if (DEBUG) Log.d(TAG, "Process Object transaction for " + transInfo.obj.getName()); // Initiate transaction if (transInfo.objRequest) { @@ -380,7 +384,9 @@ public class Telemetry { private synchronized void processObjectUpdates(UAVObject obj, int event, boolean allInstances, boolean priority) { // Push event into queue - Log.d(TAG, "Push event into queue for obj " + obj.getName() + " event " + event); + if (DEBUG) Log.d(TAG, "Push event into queue for obj " + obj.getName() + " event " + event); + if(event == 8 && obj.getName().compareTo("GCSTelemetryStats") == 0) + Thread.dumpStack(); ObjectQueueInfo objInfo = new ObjectQueueInfo(); objInfo.obj = obj; objInfo.event = event; @@ -414,12 +420,7 @@ public class Telemetry { // If there is no transaction in progress then process event if (!transPending) { - processObjectQueue(); - - } else - { - Log.d(TAG,"Transaction pending, DO NOT process object queue..."); } } @@ -428,7 +429,7 @@ public class Telemetry { */ private synchronized void processObjectQueue() { - Log.d(TAG, "Process object queue - Depth " + objQueue.size() + " priority " + objPriorityQueue.size()); + if (DEBUG) Log.d(TAG, "Process object queue - Depth " + objQueue.size() + " priority " + objPriorityQueue.size()); // Don nothing if a transaction is already in progress (should not happen) if (transPending) @@ -460,6 +461,9 @@ public class Telemetry { objQueue.clear(); if ( objInfo.obj.getObjID() != objMngr.getObject("GCSTelemetryStats").getObjID() ) { + if (DEBUG) Log.d(TAG,"transactionCompleted(false) due to receiving object not GCSTelemetryStats while not connected."); + System.out.println(gcsStatsObj.toString()); + System.out.println(objInfo.obj.toString()); objInfo.obj.transactionCompleted(false); return; } @@ -511,6 +515,8 @@ public class Telemetry { */ private synchronized void processPeriodicUpdates() { + + if (DEBUG) Log.d(TAG, "processPeriodicUpdates()"); // Stop timer updateTimer.cancel(); diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index e2050fc25..a5885e7bc 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -57,6 +57,8 @@ public class TelemetryMonitor { */ public synchronized void startRetrievingObjects() { + Log.d(TAG, "Start retrieving objects"); + // Clear object queue queue.clear(); // Get all objects, add metaobjects, settings and data objects with OnChange update mode to the queue @@ -101,7 +103,7 @@ public class TelemetryMonitor { */ public void stopRetrievingObjects() { - //qxtLog->debug("Object retrieval has been cancelled"); + Log.d(TAG, "Stop retrieving objects"); queue.clear(); } @@ -113,6 +115,7 @@ public class TelemetryMonitor { // If queue is empty return if ( queue.isEmpty() ) { + Log.d(TAG, "All objects retrieved: Connected Successfully"); //qxtLog->debug("Object retrieval completed"); //emit connected(); return; @@ -121,8 +124,7 @@ public class TelemetryMonitor { UAVObject obj = queue.remove(0); if(obj == null) { - Log.e(TAG, "Got null object forom transaction queue"); - return; + throw new Error("Got null object forom transaction queue"); } Log.d(TAG, "Retrieving object: " + obj.getName()) ; @@ -130,6 +132,7 @@ public class TelemetryMonitor { obj.addTransactionCompleted(new Observer() { public void update(Observable observable, Object data) { UAVObject.TransactionResult result = (UAVObject.TransactionResult) data; + Log.d(TAG,"Got transaction completed event from " + result.obj.getName() + " status: " + result.success); transactionCompleted(result.obj, result.success); } }); @@ -146,11 +149,16 @@ public class TelemetryMonitor { { //QMutexLocker locker(mutex); // Disconnect from sending object - Log.d(TAG,"transactionCompleted"); + Log.d(TAG,"transactionCompleted. Status: " + success); // TODO: Need to be able to disconnect signals //obj->disconnect(this); objPending = null; + if(!success) { + Log.e(TAG, "Transaction failed: " + obj.getName() + " sending again."); + return; + } + // Process next object if telemetry is still available if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) { @@ -184,6 +192,7 @@ public class TelemetryMonitor { public synchronized void processStatsUpdates() { // Get telemetry stats + Log.d(TAG, "processStatsUpdates()"); Telemetry.TelemetryStats telStats = tel.getStats(); tel.resetStats(); @@ -221,9 +230,9 @@ public class TelemetryMonitor { return; } UAVObjectField statusField = gcsStatsObj.getField("Status"); - String oldStatus = (String) statusField.getValue(); + String oldStatus = new String((String) statusField.getValue()); - System.out.println("GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); + Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); if ( oldStatus.compareTo("Disconnected") == 0 ) { @@ -236,7 +245,7 @@ public class TelemetryMonitor { if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("HandshakeAck") == 0 ) { statusField.setValue("Connected"); - System.out.println("Connected" + statusField.toString()); + Log.d(TAG,"Connected" + statusField.toString()); } } else if ( oldStatus.compareTo("Connected") == 0 ) @@ -251,31 +260,31 @@ public class TelemetryMonitor { // Force telemetry update if not yet connected boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); - if(gcsStatusChanged) - System.out.println("GCS Status changed"); + if(gcsStatusChanged) { + Log.d(TAG,"GCS Status changed"); + Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); + } boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; + boolean flightConnected = ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0; - if ( gcsStatusChanged || - ((String) flightStatsObj.getField("Status").getValue()).compareTo("Disconnected") != 0 ) + if ( !gcsConnected || !flightConnected ) { - System.out.println("Sending gcs status\n\n\n"); + Log.d(TAG,"Sending gcs status"); gcsStatsObj.updated(); } // Act on new connections or disconnections if (gcsConnected && gcsStatusChanged) { + Log.d(TAG,"Connection with the autopilot established"); setPeriod(STATS_UPDATE_PERIOD_MS); - System.out.println(TAG + " Connection with the autopilot established"); - //Log.d(TAG,"Connection with the autopilot established"); startRetrievingObjects(); } if (gcsDisconnected && gcsStatusChanged) { + Log.d(TAG,"Trying to connect to the autopilot"); setPeriod(STATS_CONNECT_PERIOD_MS); - System.out.println(TAG + " Connection with the autopilot lost"); - //Log.d(TAG,"Trying to connect to the autopilot"); //emit disconnected(); } } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index b74df9218..ba3bf1ae3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -102,6 +102,18 @@ public abstract class UAVObject { } } + private CallbackListener updateRequestedListeners = new CallbackListener(this); + public void addUpdateRequestedObserver(Observer o) { + synchronized(updateRequestedListeners) { + updateRequestedListeners.addObserver(o); + } + } + void updateRequested() { + synchronized(updateRequestedListeners) { + updateRequestedListeners.event(); + } + } + public abstract boolean isMetadata(); /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 8d792bb39..de2059e90 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -358,7 +358,7 @@ public class UAVObjectField { //throw new Exception("Sorry I haven't implemented strings yet"); } } - obj.updated(); + //obj.updated(); } } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 825f9d9fe..33daefab7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -9,49 +9,66 @@ import java.nio.ByteBuffer; import java.nio.ByteOrder; import java.util.Observable; -public class UAVTalk extends Observable{ +import android.util.Log; + +public class UAVTalk extends Observable { + + static final String TAG = "UAVTalk"; + public static int LOGLEVEL = 0; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; private Thread inputProcessingThread = null; + /** * A reference to the thread for processing the incoming stream + * * @return */ public Thread getInputProcessThread() { - if(inputProcessingThread == null) + if (inputProcessingThread == null) inputProcessingThread = new Thread() { - public void run() { - processInputStream(); - } - }; + public void run() { + processInputStream(); + } + }; return inputProcessingThread; } - + /** * Constants */ private static final int SYNC_VAL = 0x3C; - private static final short crc_table[] = { - 0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d, - 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, - 0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd, - 0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, 0xb4, 0xb3, 0xba, 0xbd, - 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, - 0xb7, 0xb0, 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a, - 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a, - 0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, - 0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4, - 0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, 0xd4, - 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, - 0x19, 0x1e, 0x17, 0x10, 0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34, - 0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f, 0x6a, 0x6d, 0x64, 0x63, - 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, - 0xae, 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83, - 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3 - }; + private static final short crc_table[] = { 0x00, 0x07, 0x0e, 0x09, 0x1c, + 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d, + 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, + 0x41, 0x54, 0x53, 0x5a, 0x5d, 0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, + 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd, 0x90, + 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, + 0xb4, 0xb3, 0xba, 0xbd, 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, + 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, 0xb7, 0xb0, + 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, + 0x94, 0x9d, 0x9a, 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, + 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a, 0x57, 0x50, 0x59, + 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, + 0x7d, 0x7a, 0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, + 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4, 0xf9, 0xfe, 0xf7, 0xf0, + 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, + 0xd4, 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, + 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, 0x19, 0x1e, 0x17, 0x10, 0x05, + 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34, + 0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, + 0x7f, 0x6a, 0x6d, 0x64, 0x63, 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, + 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, 0xae, + 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, + 0x8a, 0x8d, 0x84, 0x83, 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, + 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3 }; - enum RxStateType {STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS}; + enum RxStateType { + STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS + }; static final int TYPE_MASK = 0xFC; static final int TYPE_VER = 0x20; @@ -60,17 +77,21 @@ public class UAVTalk extends Observable{ static final int TYPE_OBJ_ACK = (TYPE_VER | 0x02); static final int TYPE_ACK = (TYPE_VER | 0x03); - static final int MIN_HEADER_LENGTH = 8; // sync(1), type (1), size(2), object ID(4) - static final int MAX_HEADER_LENGTH = 10; // sync(1), type (1), size(2), object ID (4), instance ID(2, not used in single objects) + static final int MIN_HEADER_LENGTH = 8; // sync(1), type (1), size(2), + // object ID(4) + static final int MAX_HEADER_LENGTH = 10; // sync(1), type (1), size(2), + // object ID (4), instance ID(2, + // not used in single objects) static final int CHECKSUM_LENGTH = 1; static final int MAX_PAYLOAD_LENGTH = 256; - static final int MAX_PACKET_LENGTH = (MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH); + static final int MAX_PACKET_LENGTH = (MAX_HEADER_LENGTH + + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH); static final int ALL_INSTANCES = 0xFFFF; - static final int TX_BUFFER_SIZE = 2*1024; + static final int TX_BUFFER_SIZE = 2 * 1024; /** * Private data @@ -93,12 +114,12 @@ public class UAVTalk extends Observable{ int rxCSPacket, rxCS; int rxCount; int packetSize; - RxStateType rxState; + RxStateType rxState; ComStats stats = new ComStats(); /** * Comm stats - */ + */ public class ComStats { public int txBytes = 0; public int rxBytes = 0; @@ -113,8 +134,8 @@ public class UAVTalk extends Observable{ /** * Constructor */ - public UAVTalk(InputStream inStream, OutputStream outStream, UAVObjectManager objMngr) - { + public UAVTalk(InputStream inStream, OutputStream outStream, + UAVObjectManager objMngr) { this.objMngr = objMngr; this.inStream = inStream; this.outStream = outStream; @@ -122,7 +143,7 @@ public class UAVTalk extends Observable{ rxState = RxStateType.STATE_SYNC; rxPacketLength = 0; - //mutex = new QMutex(QMutex::Recursive); + // mutex = new QMutex(QMutex::Recursive); respObj = null; resetStats(); @@ -131,88 +152,80 @@ public class UAVTalk extends Observable{ rxBuffer = ByteBuffer.allocate(MAX_PAYLOAD_LENGTH); rxBuffer.order(ByteOrder.LITTLE_ENDIAN); - // TOOD: Callback connect(io, SIGNAL(readyRead()), this, SLOT(processInputStream())); + // TOOD: Callback connect(io, SIGNAL(readyRead()), this, + // SLOT(processInputStream())); } /** * Reset the statistics counters */ - public void resetStats() - { - //QMutexLocker locker(mutex); + public void resetStats() { + // QMutexLocker locker(mutex); stats = new ComStats(); } /** * Get the statistics counters */ - public ComStats getStats() - { - //QMutexLocker locker(mutex); + public ComStats getStats() { + // QMutexLocker locker(mutex); return stats; } /** * Called each time there are data in the input buffer */ - public void processInputStream() - { + public void processInputStream() { int val; - - while (true) - { + + while (true) { try { - //inStream.wait(); + // inStream.wait(); val = inStream.read(); - } /*catch (InterruptedException e) { - // TODO Auto-generated catch block - System.out.println("Connection was aborted\n"); - e.printStackTrace(); - break; - }*/ catch (IOException e) { + } /* + * catch (InterruptedException e) { // TODO Auto-generated catch + * block System.out.println("Connection was aborted\n"); + * e.printStackTrace(); break; } + */catch (IOException e) { // TODO Auto-generated catch block System.out.println("Error reading from stream\n"); e.printStackTrace(); break; } - if(val == -1) { - System.out.println("End of stream, terminating processInputStream thread"); + if (val == -1) { + System.out + .println("End of stream, terminating processInputStream thread"); break; } - - //System.out.println("Received byte " + val + " in state + " + rxState); + + // System.out.println("Received byte " + val + " in state + " + + // rxState); processInputByte(val); } } /** - * Request an update for the specified object, on success the object data would have been - * updated by the GCS. - * \param[in] obj Object to update + * Request an update for the specified object, on success the object data + * would have been updated by the GCS. \param[in] obj Object to update * \param[in] allInstances If set true then all instances will be updated * \return Success (true), Failure (false) */ - public boolean sendObjectRequest(UAVObject obj, boolean allInstances) - { - //QMutexLocker locker(mutex); + public boolean sendObjectRequest(UAVObject obj, boolean allInstances) { + // QMutexLocker locker(mutex); return objectTransaction(obj, TYPE_OBJ_REQ, allInstances); } /** - * Send the specified object through the telemetry link. - * \param[in] obj Object to send - * \param[in] acked Selects if an ack is required - * \param[in] allInstances If set true then all instances will be updated - * \return Success (true), Failure (false) + * Send the specified object through the telemetry link. \param[in] obj + * Object to send \param[in] acked Selects if an ack is required \param[in] + * allInstances If set true then all instances will be updated \return + * Success (true), Failure (false) */ - public synchronized boolean sendObject(UAVObject obj, boolean acked, boolean allInstances) - { - if (acked) - { + public synchronized boolean sendObject(UAVObject obj, boolean acked, + boolean allInstances) { + if (acked) { return objectTransaction(obj, TYPE_OBJ_ACK, allInstances); - } - else - { + } else { return objectTransaction(obj, TYPE_OBJ, allInstances); } } @@ -220,64 +233,49 @@ public class UAVTalk extends Observable{ /** * Cancel a pending transaction */ - public synchronized void cancelTransaction() - { + public synchronized void cancelTransaction() { respObj = null; } /** - * Execute the requested transaction on an object. - * \param[in] obj Object - * \param[in] type Transaction type - * TYPE_OBJ: send object, - * TYPE_OBJ_REQ: request object update - * TYPE_OBJ_ACK: send object with an ack - * \param[in] allInstances If set true then all instances will be updated - * \return Success (true), Failure (false) + * Execute the requested transaction on an object. \param[in] obj Object + * \param[in] type Transaction type TYPE_OBJ: send object, TYPE_OBJ_REQ: + * request object update TYPE_OBJ_ACK: send object with an ack \param[in] + * allInstances If set true then all instances will be updated \return + * Success (true), Failure (false) */ - public boolean objectTransaction(UAVObject obj, int type, boolean allInstances) - { + public boolean objectTransaction(UAVObject obj, int type, + boolean allInstances) { // Send object depending on if a response is needed - if (type == TYPE_OBJ_ACK || type == TYPE_OBJ_REQ) - { - if ( transmitObject(obj, type, allInstances) ) - { + if (type == TYPE_OBJ_ACK || type == TYPE_OBJ_REQ) { + if (transmitObject(obj, type, allInstances)) { respObj = obj; - respAllInstances = allInstances; + respAllInstances = allInstances; return true; - } - else - { + } else { return false; } - } - else if (type == TYPE_OBJ) - { + } else if (type == TYPE_OBJ) { return transmitObject(obj, TYPE_OBJ, allInstances); - } - else - { + } else { return false; } } /** - * Process an byte from the telemetry stream. - * \param[in] rxbyte Received byte - * \return Success (true), Failure (false) + * Process an byte from the telemetry stream. \param[in] rxbyte Received + * byte \return Success (true), Failure (false) */ - public synchronized boolean processInputByte(int rxbyte) - { - assert(objMngr != null); + public synchronized boolean processInputByte(int rxbyte) { + assert (objMngr != null); // Update stats stats.rxBytes++; - rxPacketLength++; // update packet byte count + rxPacketLength++; // update packet byte count // Receive state machine - switch (rxState) - { + switch (rxState) { case STATE_SYNC: if (rxbyte != SYNC_VAL) @@ -296,8 +294,7 @@ public class UAVTalk extends Observable{ // Update CRC rxCS = updateCRC(rxCS, rxbyte); - if ((rxbyte & TYPE_MASK) != TYPE_VER) - { + if ((rxbyte & TYPE_MASK) != TYPE_VER) { rxState = RxStateType.STATE_SYNC; break; } @@ -315,8 +312,7 @@ public class UAVTalk extends Observable{ // Update CRC rxCS = updateCRC(rxCS, rxbyte); - if (rxCount == 0) - { + if (rxCount == 0) { packetSize += rxbyte; rxCount++; break; @@ -324,10 +320,12 @@ public class UAVTalk extends Observable{ packetSize += (rxbyte << 8) & 0xff00; - if (packetSize < MIN_HEADER_LENGTH || packetSize > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH) - { // incorrect packet size + if (packetSize < MIN_HEADER_LENGTH + || packetSize > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH) { // incorrect + // packet + // size rxState = RxStateType.STATE_SYNC; - break; + break; } rxCount = 0; @@ -348,8 +346,7 @@ public class UAVTalk extends Observable{ rxObjId = rxTmpBuffer.getInt(0); { UAVObject rxObj = objMngr.getObject(rxObjId); - if (rxObj == null) - { + if (rxObj == null) { stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -361,38 +358,38 @@ public class UAVTalk extends Observable{ else rxLength = rxObj.getNumBytes(); - // Check length and determine next state - if (rxLength >= MAX_PAYLOAD_LENGTH) - { - stats.rxErrors++; - rxState = RxStateType.STATE_SYNC; - break; - } + // Check length and determine next state + if (rxLength >= MAX_PAYLOAD_LENGTH) { + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } - // Check the lengths match - if ((rxPacketLength + rxLength) != packetSize) - { // packet error - mismatched packet size - stats.rxErrors++; - rxState = RxStateType.STATE_SYNC; - break; - } + // Check the lengths match + if ((rxPacketLength + rxLength) != packetSize) { // packet error + // - + // mismatched + // packet + // size + stats.rxErrors++; + rxState = RxStateType.STATE_SYNC; + break; + } - // Check if this is a single instance object (i.e. if the instance ID field is coming next) - if (rxObj.isSingleInstance()) - { - // If there is a payload get it, otherwise receive checksum - if (rxLength > 0) - rxState = RxStateType.STATE_DATA; - else - rxState = RxStateType.STATE_CS; - rxInstId = 0; - rxCount = 0; - } + // Check if this is a single instance object (i.e. if the + // instance ID field is coming next) + if (rxObj.isSingleInstance()) { + // If there is a payload get it, otherwise receive checksum + if (rxLength > 0) + rxState = RxStateType.STATE_DATA; else - { - rxState = RxStateType.STATE_INSTID; - rxCount = 0; - } + rxState = RxStateType.STATE_CS; + rxInstId = 0; + rxCount = 0; + } else { + rxState = RxStateType.STATE_INSTID; + rxCount = 0; + } } break; @@ -419,7 +416,7 @@ public class UAVTalk extends Observable{ break; case STATE_DATA: - + // Update CRC rxCS = updateCRC(rxCS, rxbyte); @@ -436,15 +433,15 @@ public class UAVTalk extends Observable{ // The CRC byte rxCSPacket = rxbyte; - if (rxCS != rxCSPacket) - { // packet error - faulty CRC + if (rxCS != rxCSPacket) { // packet error - faulty CRC stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; } - if (rxPacketLength != (packetSize + 1)) - { // packet error - mismatched packet size + if (rxPacketLength != (packetSize + 1)) { // packet error - + // mismatched packet + // size stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -468,103 +465,84 @@ public class UAVTalk extends Observable{ } /** - * Receive an object. This function process objects received through the telemetry stream. - * \param[in] type Type of received message (TYPE_OBJ, TYPE_OBJ_REQ, TYPE_OBJ_ACK, TYPE_ACK) - * \param[in] obj Handle of the received object - * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. - * \param[in] data Data buffer - * \param[in] length Buffer length - * \return Success (true), Failure (false) + * Receive an object. This function process objects received through the + * telemetry stream. \param[in] type Type of received message (TYPE_OBJ, + * TYPE_OBJ_REQ, TYPE_OBJ_ACK, TYPE_ACK) \param[in] obj Handle of the + * received object \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES + * for all instances. \param[in] data Data buffer \param[in] length Buffer + * length \return Success (true), Failure (false) */ - public boolean receiveObject(int type, int objId, int instId, ByteBuffer data) - { - assert(objMngr != null); - + public boolean receiveObject(int type, int objId, int instId, + ByteBuffer data) { + assert (objMngr != null); + UAVObject obj = null; boolean error = false; - boolean allInstances = (instId == ALL_INSTANCES? true : false); + boolean allInstances = (instId == ALL_INSTANCES ? true : false); // Process message type switch (type) { case TYPE_OBJ: // All instances, not allowed for OBJ messages - if (!allInstances) - { - System.out.println("Received object: " + objMngr.getObject(objId).getName()); + if (!allInstances) { + if (DEBUG) Log.d(TAG,"Received object: " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Check if an ack is pending - if ( obj != null ) - { + if (obj != null) { updateAck(obj); - } - else - { + } else { error = true; } - } - else - { + } else { error = true; } break; case TYPE_OBJ_ACK: // All instances, not allowed for OBJ_ACK messages - if (!allInstances) - { -// System.out.println("Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); + if (!allInstances) { + // System.out.println("Received object ack: " + objId + " " + + // objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK - if ( obj != null ) - { + if (obj != null) { transmitObject(obj, TYPE_ACK, false); - } - else - { + } else { error = true; } - } - else - { + } else { error = true; } break; case TYPE_OBJ_REQ: - // Get object, if all instances are requested get instance 0 of the object -// System.out.println("Received object request: " + objId + " " + objMngr.getObject(objId).getName()); - if (allInstances) - { + // Get object, if all instances are requested get instance 0 of the + // object + // System.out.println("Received object request: " + objId + " " + + // objMngr.getObject(objId).getName()); + if (allInstances) { obj = objMngr.getObject(objId); - } - else - { + } else { obj = objMngr.getObject(objId, instId); } // If object was found transmit it - if (obj != null) - { + if (obj != null) { transmitObject(obj, TYPE_OBJ, allInstances); - } - else - { + } else { error = true; } break; case TYPE_ACK: // All instances, not allowed for ACK messages - if (!allInstances) - { -// System.out.println("Received ack: " + objId + " " + objMngr.getObject(objId).getName()); + if (!allInstances) { + // System.out.println("Received ack: " + objId + " " + + // objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending - if (obj != null) - { + if (obj != null) { updateAck(obj); - } - else - { + } else { error = true; } } @@ -577,23 +555,20 @@ public class UAVTalk extends Observable{ } /** - * Update the data of an object from a byte array (unpack). - * If the object instance could not be found in the list, then a - * new one is created. + * Update the data of an object from a byte array (unpack). If the object + * instance could not be found in the list, then a new one is created. */ - public synchronized UAVObject updateObject(int objId, int instId, ByteBuffer data) - { - assert(objMngr != null); + public synchronized UAVObject updateObject(int objId, int instId, + ByteBuffer data) { + assert (objMngr != null); // Get object UAVObject obj = objMngr.getObject(objId, instId); // If the instance does not exist create it - if (obj == null) - { + if (obj == null) { // Get the object type UAVObject tobj = objMngr.getObject(objId); - if (tobj == null) - { + if (tobj == null) { return null; } // Make sure this is a data object @@ -604,26 +579,26 @@ public class UAVTalk extends Observable{ // Failed to cast to a data object return null; } - + // Create a new instance, unpack and register UAVDataObject instobj = dobj.clone(instId); try { - if ( !objMngr.registerObject(instobj) ) - { + if (!objMngr.registerObject(instobj)) { return null; } } catch (Exception e) { // TODO Auto-generated catch block e.printStackTrace(); } -// System.out.println("Unpacking new object"); + // System.out.println("Unpacking new object"); + if (DEBUG) Log.d(TAG, "Unpacking new object"); instobj.unpack(data); return instobj; - } - else - { + } else { // Unpack data into object instance -// System.out.println("Unpacking existing object: " + data.position() + " / " + data.capacity() ); + // System.out.println("Unpacking existing object: " + + // data.position() + " / " + data.capacity() ); + if (DEBUG) Log.d(TAG, "Unpacking existing object: " + obj.getName()); obj.unpack(data); return obj; } @@ -632,10 +607,9 @@ public class UAVTalk extends Observable{ /** * Check if a transaction is pending and if yes complete it. */ - public void updateAck(UAVObject obj) - { - if (respObj != null && respObj.getObjID() == obj.getObjID() && (respObj.getInstID() == obj.getInstID() || respAllInstances)) - { + synchronized void updateAck(UAVObject obj) { + if (respObj != null && respObj.getObjID() == obj.getObjID() + && (respObj.getInstID() == obj.getInstID() || respAllInstances)) { respObj = null; setChanged(); notifyObservers(obj); @@ -643,111 +617,88 @@ public class UAVTalk extends Observable{ } /** - * Send an object through the telemetry link. - * \param[in] obj Object to send - * \param[in] type Transaction type - * \param[in] allInstances True is all instances of the object are to be sent - * \return Success (true), Failure (false) + * Send an object through the telemetry link. + * @param[in] obj Object to send + * @param[in] type Transaction type + * @param[in] allInstances True is all instances of the object are to be sent + * @return Success (true), Failure (false) */ - public boolean transmitObject(UAVObject obj, int type, boolean allInstances) - { - // If all instances are requested on a single instance object it is an error - if (allInstances && obj.isSingleInstance()) - { + public synchronized boolean transmitObject(UAVObject obj, int type, boolean allInstances) { + // If all instances are requested on a single instance object it is an + // error + if (allInstances && obj.isSingleInstance()) { allInstances = false; } // Process message type - if ( type == TYPE_OBJ || type == TYPE_OBJ_ACK ) - { - if (allInstances) - { + if (type == TYPE_OBJ || type == TYPE_OBJ_ACK) { + if (allInstances) { // Get number of instances int numInst = objMngr.getNumInstances(obj.getObjID()); // Send all instances - for (int instId = 0; instId < numInst; ++instId) - { + for (int instId = 0; instId < numInst; ++instId) { UAVObject inst = objMngr.getObject(obj.getObjID(), instId); transmitSingleObject(inst, type, false); } return true; - } - else - { + } else { return transmitSingleObject(obj, type, false); } - } - else if (type == TYPE_OBJ_REQ) - { + } else if (type == TYPE_OBJ_REQ) { return transmitSingleObject(obj, TYPE_OBJ_REQ, allInstances); - } - else if (type == TYPE_ACK) - { - if (!allInstances) - { + } else if (type == TYPE_ACK) { + if (!allInstances) { return transmitSingleObject(obj, TYPE_ACK, false); - } - else - { + } else { return false; } - } - else - { + } else { return false; } } - /** - * Send an object through the telemetry link. - * \param[in] obj Object handle to send - * \param[in] type Transaction type - * \return Success (true), Failure (false) + * Send an object through the telemetry link. \param[in] obj Object handle + * to send \param[in] type Transaction type \return Success (true), Failure + * (false) */ - public synchronized boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) - { + public synchronized boolean transmitSingleObject(UAVObject obj, int type, + boolean allInstances) { int length; int dataOffset; int objId; int instId; int allInstId = ALL_INSTANCES; - - assert(objMngr != null && outStream != null); - + + assert (objMngr != null && outStream != null); + ByteBuffer bbuf = ByteBuffer.allocate(MAX_PACKET_LENGTH); bbuf.order(ByteOrder.LITTLE_ENDIAN); // Determine data length - if (type == TYPE_OBJ_REQ || type == TYPE_ACK) - { + if (type == TYPE_OBJ_REQ || type == TYPE_ACK) { length = 0; - } - else - { + } else { length = obj.getNumBytes(); } - + // Setup type and object id fields bbuf.put((byte) (SYNC_VAL & 0xff)); bbuf.put((byte) (type & 0xff)); - bbuf.putShort((short) (length + - 2 /* SYNC, Type */ + - 2 /* Size */ + - 4 /* ObjID */ + - (obj.isSingleInstance() ? 0 : 2) )); + bbuf + .putShort((short) (length + 2 /* SYNC, Type */+ 2 /* Size */+ 4 /* ObjID */+ (obj + .isSingleInstance() ? 0 : 2))); bbuf.putInt(obj.getObjID()); - + // Setup instance ID if one is required - if ( !obj.isSingleInstance() ) - { + if (!obj.isSingleInstance()) { // Check if all instances are requested if (allInstances) bbuf.putShort((short) (allInstId & 0xffff)); else bbuf.putShort((short) (obj.getInstID() & 0xffff)); } - + // Check length if (length >= MAX_PAYLOAD_LENGTH) return false; @@ -755,7 +706,7 @@ public class UAVTalk extends Observable{ // Copy data (if any) if (length > 0) try { - if ( obj.pack(bbuf) == 0) + if (obj.pack(bbuf) == 0) return false; } catch (Exception e) { // TODO Auto-generated catch block @@ -769,26 +720,28 @@ public class UAVTalk extends Observable{ try { int packlen = bbuf.position(); bbuf.position(0); - byte [] dst = new byte[packlen]; - bbuf.get(dst,0,packlen); + byte[] dst = new byte[packlen]; + bbuf.get(dst, 0, packlen); outStream.write(dst); } catch (IOException e) { // TODO Auto-generated catch block e.printStackTrace(); return false; } - -// //TODO: Need to use a different outStream type and check that the backlog isn't more than TX_BUFFER_SIZE -// // Send buffer, check that the transmit backlog does not grow above limit -// if ( io->bytesToWrite() < TX_BUFFER_SIZE ) -// { -// io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH); -// } -// else -// { -// ++stats.txErrors; -// return false; -// } + + // //TODO: Need to use a different outStream type and check that the + // backlog isn't more than TX_BUFFER_SIZE + // // Send buffer, check that the transmit backlog does not grow above + // limit + // if ( io->bytesToWrite() < TX_BUFFER_SIZE ) + // { + // io->write((const char*)txBuffer, dataOffset+length+CHECKSUM_LENGTH); + // } + // else + // { + // ++stats.txErrors; + // return false; + // } // Update stats ++stats.txObjects; @@ -801,33 +754,23 @@ public class UAVTalk extends Observable{ /** * Update the crc value with new data. - * - * Generated by pycrc v0.7.5, http://www.tty1.net/pycrc/ - * using the configuration: - * Width = 8 - * Poly = 0x07 - * XorIn = 0x00 - * ReflectIn = False - * XorOut = 0x00 - * ReflectOut = False - * Algorithm = table-driven - * - * \param crc The current crc value. - * \param data Pointer to a buffer of \a data_len bytes. - * \param length Number of bytes in the \a data buffer. - * \return The updated crc value. + * + * Generated by pycrc v0.7.5, http://www.tty1.net/pycrc/ using the + * configuration: Width = 8 Poly = 0x07 XorIn = 0x00 ReflectIn = False + * XorOut = 0x00 ReflectOut = False Algorithm = table-driven + * + * \param crc The current crc value. \param data Pointer to a buffer of \a + * data_len bytes. \param length Number of bytes in the \a data buffer. + * \return The updated crc value. */ - int updateCRC(int crc, int data) - { + int updateCRC(int crc, int data) { return crc_table[crc ^ (data & 0xff)]; } - int updateCRC(int crc, byte [] data, int length) - { + + int updateCRC(int crc, byte[] data, int length) { for (int i = 0; i < length; i++) crc = updateCRC(crc, (int) data[i]); - return crc; + return crc; } - - } From cdac9d7f9e897acea31e63ba53f226a90b7dc2fe Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 17 Mar 2011 13:57:18 -0500 Subject: [PATCH 226/543] Make the UAVTalk object process one byte per call so it can be embedded in another loop. Also clean up some warnings. --- .../src/org/openpilot/uavtalk/UAVTalk.java | 59 +++++++++---------- 1 file changed, 28 insertions(+), 31 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 33daefab7..8671cdef9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -1,7 +1,5 @@ package org.openpilot.uavtalk; -import java.io.ByteArrayInputStream; -import java.io.ByteArrayOutputStream; import java.io.IOException; import java.io.InputStream; import java.io.OutputStream; @@ -30,7 +28,10 @@ public class UAVTalk extends Observable { inputProcessingThread = new Thread() { public void run() { - processInputStream(); + while(true) { + if( !processInputStream() ) + break; + } } }; return inputProcessingThread; @@ -173,37 +174,36 @@ public class UAVTalk extends Observable { } /** - * Called each time there are data in the input buffer + * Process any data in the queue */ - public void processInputStream() { + public boolean processInputStream() { int val; - while (true) { - try { - // inStream.wait(); - val = inStream.read(); - } /* - * catch (InterruptedException e) { // TODO Auto-generated catch - * block System.out.println("Connection was aborted\n"); - * e.printStackTrace(); break; } - */catch (IOException e) { - // TODO Auto-generated catch block - System.out.println("Error reading from stream\n"); - e.printStackTrace(); - break; - } - if (val == -1) { - System.out - .println("End of stream, terminating processInputStream thread"); - break; - } + try { + // inStream.wait(); + val = inStream.read(); + } /* + * catch (InterruptedException e) { // TODO Auto-generated catch + * block System.out.println("Connection was aborted\n"); + * e.printStackTrace(); break; } + */catch (IOException e) { + // TODO Auto-generated catch block + System.out.println("Error reading from stream\n"); + e.printStackTrace(); + return false; + } + if (val == -1) { + System.out.println("End of stream, terminating processInputStream thread"); + return false; + } - // System.out.println("Received byte " + val + " in state + " + - // rxState); - processInputByte(val); - } + // System.out.println("Received byte " + val + " in state + " + + // rxState); + processInputByte(val); + return true; } + /** * Request an update for the specified object, on success the object data * would have been updated by the GCS. \param[in] obj Object to update @@ -665,9 +665,6 @@ public class UAVTalk extends Observable { public synchronized boolean transmitSingleObject(UAVObject obj, int type, boolean allInstances) { int length; - int dataOffset; - int objId; - int instId; int allInstId = ALL_INSTANCES; assert (objMngr != null && outStream != null); From d3f9c979613e547992ac1ebcd550b2cff8d252af Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 17 Mar 2011 13:58:55 -0500 Subject: [PATCH 227/543] Create a UAVTalk service that is called from the object browser --- androidgcs/AndroidManifest.xml | 1 + .../androidgcs/BluetoothUAVTalk.java | 146 ++++++++++++++++++ .../androidgcs/OPTelemetryService.java | 88 +++++++++++ .../openpilot/androidgcs/ObjectBrowser.java | 97 +----------- 4 files changed, 238 insertions(+), 94 deletions(-) create mode 100644 androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 8b3a9e4b3..6c89f2632 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -18,5 +18,6 @@ + \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java new file mode 100644 index 000000000..b240f3adc --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java @@ -0,0 +1,146 @@ +package org.openpilot.androidgcs; + +import java.io.IOException; +import java.util.Set; +import java.util.UUID; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVTalk; + +import android.app.Activity; +import android.bluetooth.BluetoothAdapter; +import android.bluetooth.BluetoothDevice; +import android.bluetooth.BluetoothSocket; +import android.content.BroadcastReceiver; +import android.content.Context; +import android.content.Intent; +import android.util.Log; + +public class BluetoothUAVTalk { + private final String TAG = "BluetoothUAVTalk"; + public static int LOGLEVEL = 2; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + + // Temporarily define fixed device name + public final static String DEVICE_NAME = "RN42-222D"; + private final static UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); + + private BluetoothAdapter mBluetoothAdapter; + private BluetoothSocket socket; + private BluetoothDevice device; + private UAVTalk uavTalk; + private boolean connected; + + public BluetoothUAVTalk(Context caller, String deviceName) { + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + deviceName); + + connected = false; + device = null; + + mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); + if (mBluetoothAdapter == null) { + // Device does not support Bluetooth + Log.e(TAG, "Device does not support Bluetooth"); + return; + } + + if (!mBluetoothAdapter.isEnabled()) { + // Enable bluetooth if it isn't already + Intent enableBtIntent = new Intent(BluetoothAdapter.ACTION_REQUEST_ENABLE); + caller.sendOrderedBroadcast(enableBtIntent, "android.permission.BLUETOOTH_ADMIN", new BroadcastReceiver() { + @Override + public void onReceive(Context context, Intent intent) { + Log.e(TAG,"Received " + context + intent); + //TODO: some logic here to see if it worked + queryDevices(); + } + }, null, Activity.RESULT_OK, null, null); + } else { + queryDevices(); + } + } + + public boolean connect(UAVObjectManager objMngr) { + if( getConnected() ) + return true; + if( !getFoundDevice() ) + return false; + if( !openTelemetryBluetooth(objMngr) ) + return false; + return true; + } + + public boolean getConnected() { + return connected; + } + + public boolean getFoundDevice() { + return (device != null); + } + + public UAVTalk getUavtalk() { + return uavTalk; + } + + private void queryDevices() { + Log.d(TAG, "Searching for devices"); + Set pairedDevices = mBluetoothAdapter.getBondedDevices(); + // If there are paired devices + if (pairedDevices.size() > 0) { + // Loop through paired devices + for (BluetoothDevice device : pairedDevices) { + // Add the name and address to an array adapter to show in a ListView + //mArrayAdapter.add(device.getName() + "\n" + device.getAddress()); + Log.d(TAG, "Paired device: " + device.getName()); + if(device.getName().compareTo(DEVICE_NAME) == 0) { + this.device = device; + return; + } + } + } + + } + + private boolean openTelemetryBluetooth(UAVObjectManager objMngr) { + Log.d(TAG, "Opening conncetion to " + device.getName()); + socket = null; + connected = false; + try { + socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); + } catch (IOException e) { + Log.e(TAG,"Unable to create Rfcomm socket"); + return false; + //e.printStackTrace(); + } + + mBluetoothAdapter.cancelDiscovery(); + + try { + socket.connect(); + } + catch (IOException e) { + Log.e(TAG,"Unable to connect to requested device", e); + try { + socket.close(); + } catch (IOException e2) { + Log.e(TAG, "unable to close() socket during connection failure", e2); + } + return false; + } + + connected = true; + + try { + uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); + } catch (IOException e) { + Log.e(TAG,"Error starting UAVTalk"); + // TODO Auto-generated catch block + //e.printStackTrace(); + return false; + } + + return true; + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java new file mode 100644 index 000000000..2994be6d2 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -0,0 +1,88 @@ +package org.openpilot.androidgcs; + +import org.openpilot.uavtalk.Telemetry; +import org.openpilot.uavtalk.TelemetryMonitor; +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVTalk; +import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; + +import android.app.Service; +import android.content.Intent; +import android.os.IBinder; +import android.os.Looper; +import android.util.Log; + +public class OPTelemetryService extends Service { + private final String TAG = "OPTElemetryService"; + public static int LOGLEVEL = 2; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + + private UAVObjectManager objMngr; + private UAVTalk uavTalk; + private Telemetry tel; + private TelemetryMonitor mon; + + @Override + public IBinder onBind(Intent arg0) { + return null; + } + + @Override + public void onCreate() { + super.onCreate(); + + if (DEBUG) Log.d(TAG, "Telemetry Service started"); + + Thread telemetryThread = new Thread(telemetryRunnable); + telemetryThread.start(); + } + + @Override + public void onDestroy() { + super.onDestroy(); + } + + private final Runnable telemetryRunnable = new Runnable() { + + public void run() { + Looper.prepare(); + + if (DEBUG) Log.d(TAG, "Telemetry Thread started"); + + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + + BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this, BluetoothUAVTalk.DEVICE_NAME); + while(true) { + if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); + if(! bt.getConnected() ) + bt.connect(objMngr); + else + break; + Looper.loop(); + } + + if (DEBUG) Log.d(TAG, "Connected via bluetooth"); + + uavTalk = bt.getUavtalk(); + tel = new Telemetry(uavTalk, objMngr); + mon = new TelemetryMonitor(objMngr,tel); + + if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); + while(true) { + if( !uavTalk.processInputStream() ) + break; + Looper.loop(); + } + if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); + } + + }; + + public UAVObjectManager getObjMngr() { return objMngr; }; + public UAVTalk getUavTalk() { return uavTalk; }; + public Telemetry getTelemetry() { return tel; }; + public TelemetryMonitor getTelemetryMonitor() { return mon; }; + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index a8c58d58d..6bb217930 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -69,26 +69,12 @@ public class ObjectBrowser extends Activity { Log.d(TAG, "Launching Object Browser"); - connected = false; + Log.d(TAG, "Start OP Telemetry Service"); + startService( new Intent( this, OPTelemetryService.class ) ); objMngr = new UAVObjectManager(); UAVObjectsInitialize.register(objMngr); - mBluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); - if (mBluetoothAdapter == null) { - // Device does not support Bluetooth - Log.e(TAG, "Device does not support Bluetooth"); - return; - } - - if (!mBluetoothAdapter.isEnabled()) { - Intent enableBtIntent = new Intent(BluetoothAdapter.ACTION_REQUEST_ENABLE); - startActivityForResult(enableBtIntent, REQUEST_ENABLE_BT); - } else { - queryDevices(); - } - - UAVObject obj = objMngr.getObject("SystemStats"); if(obj != null) obj.addUpdatedObserver(new Observer() { @@ -116,84 +102,7 @@ public class ObjectBrowser extends Activity { public void update(Observable observable, Object data) { uavobjHandler.post(updateText); } - }); - - + }); } - @Override - public void onActivityResult(int requestCode, int resultCode, Intent data) { - if(requestCode == REQUEST_ENABLE_BT && resultCode == RESULT_OK) { - //Log.d(TAG, "Bluetooth started succesfully"); - queryDevices(); - } - if(requestCode == REQUEST_ENABLE_BT && resultCode != RESULT_OK) { - //Log.d(TAG, "Bluetooth could not be started"); - } - - } - - public void queryDevices() { - Log.d(TAG, "Searching for devices"); - Set pairedDevices = mBluetoothAdapter.getBondedDevices(); - // If there are paired devices - if (pairedDevices.size() > 0) { - // Loop through paired devices - for (BluetoothDevice device : pairedDevices) { - // Add the name and address to an array adapter to show in a ListView - //mArrayAdapter.add(device.getName() + "\n" + device.getAddress()); - Log.d(TAG, "Paired device: " + device.getName()); - if(device.getName().compareTo(DEVICE_NAME) == 0) { - openTelmetryBluetooth(device); - openTelmetryBluetooth(device); - } - } - } - - } - - private void openTelmetryBluetooth(BluetoothDevice device) { - Log.d(TAG, "Opening conncetion to " + device.getName()); - socket = null; - connected = false; - try { - socket = device.createInsecureRfcommSocketToServiceRecord(MY_UUID); - } catch (IOException e) { - Log.e(TAG,"Unable to create Rfcomm socket"); - //e.printStackTrace(); - } - - mBluetoothAdapter.cancelDiscovery(); - - try { - socket.connect(); - } - catch (IOException e) { - Log.e(TAG,"Unable to connect to requested device", e); - try { - socket.close(); - } catch (IOException e2) { - //Log.e(TAG, "unable to close() socket during connection failure", e2); - } - return; - } - - connected = true; - - try { - uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); - } catch (IOException e) { - Log.e(TAG,"Error starting UAVTalk"); - // TODO Auto-generated catch block - //e.printStackTrace(); - return; - } - - Thread inputStream = uavTalk.getInputProcessThread(); - inputStream.start(); - - Telemetry tel = new Telemetry(uavTalk, objMngr); - TelemetryMonitor mon = new TelemetryMonitor(objMngr,tel); - - } } From f247443d6420db79bb3afa228c4a6d9209130119 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 19 Mar 2011 10:09:35 -0500 Subject: [PATCH 228/543] Clean up the logging somewhat --- .../androidgcs/OPTelemetryService.java | 62 +- .../openpilot/uavtalk/TelemetryMonitor.java | 31 +- flight/Revolution/Makefile.osx | 672 ++++++++++++++++++ 3 files changed, 740 insertions(+), 25 deletions(-) create mode 100644 flight/Revolution/Makefile.osx diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 2994be6d2..5a48bbc05 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -6,8 +6,14 @@ import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; +import android.app.Notification; +import android.app.NotificationManager; +import android.app.PendingIntent; import android.app.Service; +import android.content.Context; import android.content.Intent; +import android.net.Uri; +import android.os.Handler; import android.os.IBinder; import android.os.Looper; import android.util.Log; @@ -18,10 +24,16 @@ public class OPTelemetryService extends Service { public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; + final int DISCONNECT_MESSAGE = 0; + final int CONNECT_MESSAGE = 1; + final int CONNECT_FAILED_MESSAGE = 2; + private UAVObjectManager objMngr; private UAVTalk uavTalk; private Telemetry tel; private TelemetryMonitor mon; + + private Handler handler; @Override public IBinder onBind(Intent arg0) { @@ -46,22 +58,38 @@ public class OPTelemetryService extends Service { private final Runnable telemetryRunnable = new Runnable() { public void run() { - Looper.prepare(); - if (DEBUG) Log.d(TAG, "Telemetry Thread started"); + + Looper.prepare(); objMngr = new UAVObjectManager(); UAVObjectsInitialize.register(objMngr); - + + postNotification(CONNECT_FAILED_MESSAGE, "Connecting"); BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this, BluetoothUAVTalk.DEVICE_NAME); - while(true) { + for( int i = 0; i < 10; i++ ) { if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); - if(! bt.getConnected() ) - bt.connect(objMngr); - else + + bt.connect(objMngr); + + if (DEBUG) Log.d(TAG, "Done attempting connection"); + if( bt.getConnected() ) break; - Looper.loop(); + + try { + Thread.sleep(1000); + } catch (InterruptedException e) { + Log.e(TAG, "Thread interrupted while trying to connect"); + e.printStackTrace(); + return; + } } + if( ! bt.getConnected() ) { + postNotification(CONNECT_FAILED_MESSAGE, "Could not connect to UAV"); + return; + } + + postNotification(CONNECT_MESSAGE, "Connected to UAV port"); if (DEBUG) Log.d(TAG, "Connected via bluetooth"); @@ -73,13 +101,29 @@ public class OPTelemetryService extends Service { while(true) { if( !uavTalk.processInputStream() ) break; - Looper.loop(); } if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); + postNotification(DISCONNECT_MESSAGE,"UAVTalk stream disconnected"); } }; + void postNotification(int id, String message) { + String ns = Context.NOTIFICATION_SERVICE; + NotificationManager mNManager = (NotificationManager) getSystemService(ns); + final Notification msg = new Notification(R.drawable.icon, message, System.currentTimeMillis()); + + Context context = getApplicationContext(); + CharSequence contentTitle = "OpenPilot"; + CharSequence contentText = message; + Intent msgIntent = new Intent(Intent.ACTION_VIEW, Uri.parse("http://forums.openpilot.org")); + PendingIntent intent = PendingIntent.getActivity(this, 0, msgIntent, Intent.FLAG_ACTIVITY_NEW_TASK); + + msg.setLatestEventInfo(context, contentTitle, contentText, intent); + + mNManager.notify(id, msg); + } + public UAVObjectManager getObjMngr() { return objMngr; }; public UAVTalk getUavTalk() { return uavTalk; }; public Telemetry getTelemetry() { return tel; }; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index a5885e7bc..9b4474d8e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -16,7 +16,10 @@ import android.util.Log; public class TelemetryMonitor { private static final String TAG = "TelemetryMonitor"; - + public static int LOGLEVEL = 0; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + static final int STATS_UPDATE_PERIOD_MS = 4000; static final int STATS_CONNECT_PERIOD_MS = 1000; static final int CONNECTION_TIMEOUT_MS = 8000; @@ -57,7 +60,7 @@ public class TelemetryMonitor { */ public synchronized void startRetrievingObjects() { - Log.d(TAG, "Start retrieving objects"); + if (DEBUG) Log.d(TAG, "Start retrieving objects"); // Clear object queue queue.clear(); @@ -115,7 +118,7 @@ public class TelemetryMonitor { // If queue is empty return if ( queue.isEmpty() ) { - Log.d(TAG, "All objects retrieved: Connected Successfully"); + if (DEBUG) Log.d(TAG, "All objects retrieved: Connected Successfully"); //qxtLog->debug("Object retrieval completed"); //emit connected(); return; @@ -127,12 +130,12 @@ public class TelemetryMonitor { throw new Error("Got null object forom transaction queue"); } - Log.d(TAG, "Retrieving object: " + obj.getName()) ; + if (DEBUG) Log.d(TAG, "Retrieving object: " + obj.getName()) ; // Connect to object obj.addTransactionCompleted(new Observer() { public void update(Observable observable, Object data) { UAVObject.TransactionResult result = (UAVObject.TransactionResult) data; - Log.d(TAG,"Got transaction completed event from " + result.obj.getName() + " status: " + result.success); + if (DEBUG) Log.d(TAG,"Got transaction completed event from " + result.obj.getName() + " status: " + result.success); transactionCompleted(result.obj, result.success); } }); @@ -149,7 +152,7 @@ public class TelemetryMonitor { { //QMutexLocker locker(mutex); // Disconnect from sending object - Log.d(TAG,"transactionCompleted. Status: " + success); + if (DEBUG) Log.d(TAG,"transactionCompleted. Status: " + success); // TODO: Need to be able to disconnect signals //obj->disconnect(this); objPending = null; @@ -192,7 +195,7 @@ public class TelemetryMonitor { public synchronized void processStatsUpdates() { // Get telemetry stats - Log.d(TAG, "processStatsUpdates()"); + if (DEBUG) Log.d(TAG, "processStatsUpdates()"); Telemetry.TelemetryStats telStats = tel.getStats(); tel.resetStats(); @@ -232,7 +235,7 @@ public class TelemetryMonitor { UAVObjectField statusField = gcsStatsObj.getField("Status"); String oldStatus = new String((String) statusField.getValue()); - Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); + if (DEBUG) Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); if ( oldStatus.compareTo("Disconnected") == 0 ) { @@ -245,7 +248,7 @@ public class TelemetryMonitor { if ( ((String) flightStatsObj.getField("Status").getValue()).compareTo("HandshakeAck") == 0 ) { statusField.setValue("Connected"); - Log.d(TAG,"Connected" + statusField.toString()); + if (DEBUG) Log.d(TAG,"Connected" + statusField.toString()); } } else if ( oldStatus.compareTo("Connected") == 0 ) @@ -260,30 +263,26 @@ public class TelemetryMonitor { // Force telemetry update if not yet connected boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); - if(gcsStatusChanged) { - Log.d(TAG,"GCS Status changed"); - Log.d(TAG,"GCS: " + statusField.getValue() + " Flight: " + flightStatsObj.getField("Status").getValue()); - } boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; boolean flightConnected = ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0; if ( !gcsConnected || !flightConnected ) { - Log.d(TAG,"Sending gcs status"); + if (DEBUG) Log.d(TAG,"Sending gcs status"); gcsStatsObj.updated(); } // Act on new connections or disconnections if (gcsConnected && gcsStatusChanged) { - Log.d(TAG,"Connection with the autopilot established"); + if (DEBUG) Log.d(TAG,"Connection with the autopilot established"); setPeriod(STATS_UPDATE_PERIOD_MS); startRetrievingObjects(); } if (gcsDisconnected && gcsStatusChanged) { - Log.d(TAG,"Trying to connect to the autopilot"); + if (DEBUG) Log.d(TAG,"Trying to connect to the autopilot"); setPeriod(STATS_CONNECT_PERIOD_MS); //emit disconnected(); } diff --git a/flight/Revolution/Makefile.osx b/flight/Revolution/Makefile.osx new file mode 100644 index 000000000..e2c8ea694 --- /dev/null +++ b/flight/Revolution/Makefile.osx @@ -0,0 +1,672 @@ + ##### + # Project: Revolution + # + # + # Makefile for OpenPilot project build PiOS and the AP. + # + # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. + # + # + # This program is free software; you can redistribute it and/or modify + # it under the terms of the GNU General Public License as published by + # the Free Software Foundation; either version 3 of the License, or + # (at your option) any later version. + # + # This program is distributed in the hope that it will be useful, but + # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + # for more details. + # + # You should have received a copy of the GNU General Public License along + # with this program; if not, write to the Free Software Foundation, Inc., + # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + ##### + + +# Set developer code and compile options +# Set to YES to compile for debugging +DEBUG ?= YES + +# Set to YES to use the Servo output pins for debugging via scope or logic analyser +ENABLE_DEBUG_PINS ?= NO + +# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs +ENABLE_AUX_UART ?= NO + +# +USE_BOOTLOADER ?= NO + + +# Set to YES when using Code Sourcery toolchain +CODE_SOURCERY ?= NO + +# Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe) +TCHAIN_PREFIX ?= /usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- + +# Remove command is different for Code Sourcery on Windows +REMOVE_CMD ?= rm + +FLASH_TOOL = OPENOCD + +# YES enables -mthumb option to flags for source-files listed +# in SRC and CPPSRC +USE_THUMB_MODE = YES + +# List of modules to include +MODULES += Actuator ManualControl Stabilization +MODULES += AltitudeHold VtolPathFollower FixedWingPathFollower PathPlanner +MODULES += Attitude/revolution +#MODULES += OveroSync/simulated + +# To run simulation instead of connect to SITL +MODULES += Sensors/simulated + +MODULES += Telemetry + +# MCU name, submodel and board +# - MCU used for compiler-option (-mtune) +# - MODEL used for linker-script name (-T) and passed as define +# - BOARD just passed as define (optional) +MCU = i686 +#CHIP = STM32F103RET +#BOARD = STM3210E_OP +MODEL = HD +ifeq ($(USE_BOOTLOADER), YES) +BOOT_MODEL = $(MODEL)_BL + +else +BOOT_MODEL = $(MODEL)_NB +endif + +# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) +OUTDIR = ../../build/sim_osx + +# Target file name (without extension). +TARGET = Revolution + +# Paths +OPSYSTEM = ./System +OPSYSTEMINC = $(OPSYSTEM)/inc +OPUAVTALK = ../UAVTalk +OPUAVTALKINC = $(OPUAVTALK)/inc +OPUAVOBJ = ../UAVObjects +OPUAVOBJINC = $(OPUAVOBJ)/inc +OPTESTS = ./Tests +OPMODULEDIR = ../Modules +FLIGHTLIB = ../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc +PIOS = ../PiOS.osx +PIOSINC = $(PIOS)/inc +PIOSPOSIX = $(PIOS)/osx +APPLIBDIR = $(PIOSPOSIX)/Libraries +RTOSDIR = $(APPLIBDIR)/FreeRTOS +RTOSSRCDIR = $(RTOSDIR)/Source +RTOSINCDIR = $(RTOSSRCDIR)/include +DOXYGENDIR = ../Doc/Doxygen +PYMITE = $(FLIGHTLIB)/PyMite +PYMITELIB = $(PYMITE)/lib +PYMITEPLAT = $(PYMITE)/platform/openpilot_sitl +PYMITETOOLS = $(PYMITE)/tools +PYMITEVM = $(PYMITE)/vm +PYMITEINC = $(PYMITEVM) +PYMITEINC += $(PYMITEPLAT) +PYMITEINC += $(OUTDIR) +FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib +FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans + +UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight +UAVOBJPYTHONSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/python + +# List C source files here. (C dependencies are automatically generated.) +# use file-extension c for "c-only"-files + +MODNAMES = $(notdir ${MODULES}) + +ifndef TESTAPP + +## PyMite files +SRC += $(OUTDIR)/pmlib_img.c +SRC += $(OUTDIR)/pmlib_nat.c +SRC += $(OUTDIR)/pmlibusr_img.c +SRC += $(OUTDIR)/pmlibusr_nat.c +SRC += $(wildcard ${PYMITEVM}/*.c) +SRC += $(wildcard ${PYMITEPLAT}/*.c) + +## MODULES +SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +SRC += ${OUTDIR}/InitMods.c +## OPENPILOT CORE: +SRC += ${OPMODULEDIR}/System/systemmod.c +SRC += $(OPSYSTEM)/revolution.c +SRC += $(OPSYSTEM)/pios_board_sim.c +SRC += $(OPSYSTEM)/alarms.c +SRC += $(OPUAVTALK)/uavtalk.c +SRC += $(OPUAVOBJ)/uavobjectmanager.c +SRC += $(OPUAVOBJ)/eventdispatcher.c +SRC += $(UAVOBJSYNTHDIR)/uavobjectsinit.c +else +## TESTCODE +SRC += $(OPTESTS)/test_common.c +SRC += $(OPTESTS)/$(TESTAPP).c +endif + + + +## UAVOBJECTS +ifndef TESTAPP +#include $(UAVOBJSYNTHDIR)/Makefile.inc +include ./UAVObjects.inc + +UAVOBJSRCFILENAMES += attitudesimulated +UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) +UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) + +SRC += $(UAVOBJSRC) +CFLAGS_UAVOBJECTS = $(UAVOBJDEFINE) +endif + +## PIOS Hardware (posix) +SRC += $(PIOSPOSIX)/pios_crc.c +SRC += $(PIOSPOSIX)/pios_sys.c +SRC += $(PIOSPOSIX)/pios_led.c +SRC += $(PIOSPOSIX)/pios_irq.c +SRC += $(PIOSPOSIX)/pios_delay.c +SRC += $(PIOSPOSIX)/pios_sdcard.c +SRC += $(PIOSPOSIX)/pios_udp.c +SRC += $(PIOSPOSIX)/pios_tcp.c +SRC += $(PIOSPOSIX)/pios_com.c +SRC += $(PIOSPOSIX)/pios_servo.c +SRC += $(PIOSPOSIX)/pios_wdg.c +SRC += $(PIOSPOSIX)/pios_debug.c + +SRC += $(PIOSPOSIX)/pios_rcvr.c +SRC += $(PIOSPOSIX)/pios_gcsrcvr.c + +## Libraries for flight calculations +SRC += $(FLIGHTLIB)/fifo_buffer.c +SRC += $(FLIGHTLIB)/WorldMagModel.c +SRC += $(FLIGHTLIB)/CoordinateConversions.c +SRC += $(FLIGHTLIB)/paths.c +SRC += $(FLIGHTLIB)/insgps13state.c +SRC += $(FLIGHTLIB)/taskmonitor.c + +## RTOS and RTOS Portable +SRC += $(RTOSSRCDIR)/list.c +SRC += $(RTOSSRCDIR)/queue.c +UNAME := $(shell uname) +SRC += $(RTOSSRCDIR)/task.c +SRC += $(RTOSSRCDIR)/timers.c +SRC += $(RTOSSRCDIR)/portable/GCC/Posix/port.c +SRC += $(RTOSSRCDIR)/portable/MemMang/heap_3.c + + + +# List C source files here which must be compiled in ARM-Mode (no -mthumb). +# use file-extension c for "c-only"-files +## just for testing, timer.c could be compiled in thumb-mode too +SRCARM = + +# List C++ source files here. +# use file-extension .cpp for C++-files (not .C) +CPPSRC = + +# List C++ source files here which must be compiled in ARM-Mode. +# use file-extension .cpp for C++-files (not .C) +#CPPSRCARM = $(TARGET).cpp +CPPSRCARM = + + +# List any extra directories to look for include files here. +# Each directory must be seperated by a space. +EXTRAINCDIRS = $(OPSYSTEM) +EXTRAINCDIRS += $(OPSYSTEMINC) +EXTRAINCDIRS += $(OPUAVTALK) +EXTRAINCDIRS += $(OPUAVTALKINC) +EXTRAINCDIRS += $(OPUAVOBJ) +EXTRAINCDIRS += $(OPUAVOBJINC) +EXTRAINCDIRS += $(UAVOBJSYNTHDIR) +EXTRAINCDIRS += $(PIOS) +EXTRAINCDIRS += $(PIOSINC) +EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(PIOSPOSIX) +EXTRAINCDIRS += $(RTOSINCDIR) +EXTRAINCDIRS += $(APPLIBDIR) +EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/Posix +EXTRAINCDIRS += $(PYMITEINC) + +EXTRAINCDIRS += ${foreach MOD, ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc + + +# List any extra directories to look for library files here. +# Also add directories where the linker should search for +# includes from linker-script to the list +# Each directory must be seperated by a space. +EXTRA_LIBDIRS = + +# Extra Libraries +# Each library-name must be seperated by a space. +# i.e. to link with libxyz.a, libabc.a and libefsl.a: +# EXTRA_LIBS = xyz abc efsl +# for newlib-lpc (file: libnewlibc-lpc.a): +# EXTRA_LIBS = newlib-lpc +EXTRA_LIBS = + +# Path to Linker-Scripts +LINKERSCRIPTPATH = $(PIOSSTM32F10X) + +# Optimization level, can be [0, 1, 2, 3, s]. +# 0 = turn off optimization. s = optimize for size. +# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) + +ifeq ($(DEBUG),YES) +OPT = 0 +else +OPT = s +endif + +# Output format. (can be ihex or binary or both) +# binary to create a load-image in raw-binary format i.e. for SAM-BA, +# ihex to create a load-image in Intel hex format +#LOADFORMAT = ihex +#LOADFORMAT = binary +LOADFORMAT = both + +# Debugging format. +#DEBUGF = dwarf-2 + +# Place project-specific -D (define) and/or +# -U options for C here. +ifeq ($(ENABLE_DEBUG_PINS), YES) +CDEFS += -DPIOS_ENABLE_DEBUG_PINS +endif +ifeq ($(ENABLE_AUX_UART), YES) +CDEFS += -DPIOS_ENABLE_AUX_UART +endif +ifeq ($(USE_BOOTLOADER), YES) +CDEFS += -DUSE_BOOTLOADER +endif + +# Compiler flag to set the C Standard level. +# c89 - "ANSI" C +# gnu89 - c89 plus GCC extensions +# c99 - ISO C99 standard (not yet fully implemented) +# gnu99 - c99 plus GCC extensions +CSTANDARD = -std=gnu99 + +#----- + +# Compiler flags. + +# -g*: generate debugging information +# -O*: optimization level +# -f...: tuning, see GCC manual and avr-libc documentation +# -Wall...: warning level +# -Wa,...: tell GCC to pass this to the assembler. +# -adhlns...: create assembler listing +# +# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) + +ifeq ($(DEBUG),YES) +CFLAGS = -g$(DEBUGF) -DDEBUG +endif + +CFLAGS += -DDIAGNOSTICS +CFLAGS += -DDIAG_TASKS + +CFLAGS += $(CFLAGS_UAVOBJECTS) +CFLAGS += -DARCH_POSIX +CFLAGS += -O$(OPT) +CFLAGS += -mtune=$(MCU) +CFLAGS += $(CDEFS) +CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. + +#CFLAGS += ARCH=arm +#CROSS_COMPILE=/usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- + +CFLAGS += -fomit-frame-pointer +ifeq ($(CODE_SOURCERY), YES) +CFLAGS += -fpromote-loop-indices +endif + +CFLAGS += -Wall +CFLAGS += -Werror +# Compiler flags to generate dependency files: +CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d + +# flags only for C +#CONLYFLAGS += -Wnested-externs +CONLYFLAGS += $(CSTANDARD) + +# Assembler flags. +# -Wa,...: tell GCC to pass this to the assembler. +# -ahlns: create listing +ASFLAGS = -mtune=$(MCU) -I. -x assembler-with-cpp +ASFLAGS += $(ADEFS) +ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) +ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) + +MATH_LIB = -lm + +# Linker flags. +# -Wl,...: tell GCC to pass this to linker. +# -Map: create map file +# --cref: add cross reference to map file +LDFLAGS += -lpthread +LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) +LDFLAGS += -lc +LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) +LDFLAGS += $(MATH_LIB) +LDFLAGS += -lc -lgcc + +# To include simulation model +LDFLAGS += -L$(OUTDIR) +#LDFLAGS += -lsimmodel + + +# Define programs and commands. +CC = $(TCHAIN_PREFIX)gcc +CPP = $(TCHAIN_PREFIX)g++ +AR = $(TCHAIN_PREFIX)ar +OBJCOPY = $(TCHAIN_PREFIX)objcopy +OBJDUMP = $(TCHAIN_PREFIX)objdump +SIZE = $(TCHAIN_PREFIX)size +NM = $(TCHAIN_PREFIX)nm +REMOVE = $(REMOVE_CMD) -f +PYTHON = python +###SHELL = sh +###COPY = cp + + + +# Define Messages +# English +MSG_ERRORS_NONE = Errors: none +MSG_BEGIN = ${quote}-------- begin (mode: $(RUN_MODE)) --------${quote} +MSG_END = ${quote}-------- end --------${quote} +MSG_MODINIT = ${quote}**** Generating ModInit.c${quote} +MSG_SIZE_BEFORE = ${quote}Size before:${quote} +MSG_SIZE_AFTER = ${quote}Size after build:${quote} +MSG_LOAD_FILE = ${quote}Creating load file:${quote} +MSG_EXTENDED_LISTING = ${quote}Creating Extended Listing/Disassembly:${quote} +MSG_SYMBOL_TABLE = ${quote}Creating Symbol Table:${quote} +MSG_LINKING = ${quote}**** Linking :${quote} +MSG_COMPILING = ${quote}**** Compiling C :${quote} +MSG_COMPILING_ARM = ${quote}**** Compiling C (ARM-only):${quote} +MSG_COMPILINGCPP = ${quote}Compiling C++ :${quote} +MSG_COMPILINGCPP_ARM = ${quote}Compiling C++ (ARM-only):${quote} +MSG_ASSEMBLING = ${quote}**** Assembling:${quote} +MSG_ASSEMBLING_ARM = ${quote}****Assembling (ARM-only):${quote} +MSG_CLEANING = ${quote}Cleaning project:${quote} +MSG_FORMATERROR = ${quote}Can not handle output-format${quote} +MSG_ASMFROMC = ${quote}Creating asm-File from C-Source:${quote} +MSG_ASMFROMC_ARM = ${quote}Creating asm-File from C-Source (ARM-only):${quote} +MSG_PYMITEINIT = ${quote}**** Generating PyMite intermediate code${quote} + +# List of all source files. +ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) +# List of all source files without directory and file-extension. +ALLSRCBASE = $(notdir $(basename $(ALLSRC))) + +# Define all object files. +ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) + +# Define all listing files (used for make clean). +LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) +# Define all depedency-files (used for make clean). +DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) + +elf: $(OUTDIR)/$(TARGET).elf +lss: $(OUTDIR)/$(TARGET).lss +sym: $(OUTDIR)/$(TARGET).sym +hex: $(OUTDIR)/$(TARGET).hex +bin: $(OUTDIR)/$(TARGET).bin + +# Default target. +#all: begin gccversion sizebefore build sizeafter finished end +#all: begin gencode gccversion build sizeafter finished end +all: elf + +ifeq ($(LOADFORMAT),ihex) +build: elf hex lss sym +else +ifeq ($(LOADFORMAT),binary) +build: elf bin lss sym +else +ifeq ($(LOADFORMAT),both) +build: elf hex bin lss sym +else +$(error "$(MSG_FORMATERROR) $(FORMAT)") +endif +endif +endif + +# Test if quotes are needed for the echo-command +result = ${shell echo "test"} +ifeq (${result}, test) + quote = ' +else + quote = +endif + +# Generate intermediate code +gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h + +getmodname = $(firstword $(subst /, ,$1)) + +MOD_GEN := $(foreach MOD,$(MODULES),$(call getmodname,$(MOD))) + +# Generate code for module initialization +${OUTDIR}/InitMods.c: Makefile.osx + echo ${MOD_GEN} + @echo ${MSG_MODINIT} + @echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Start(void);}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}void StartModules() {${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Start();}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c + +# Generate code for PyMite +${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) + @echo ${MSG_PYMITEINIT} + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) + @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py + +# Eye candy. +begin: +## @echo + @echo $(MSG_BEGIN) + +finished: +## @echo $(MSG_ERRORS_NONE) + +end: + @echo $(MSG_END) +## @echo + +# Display sizes of sections. +ELFSIZE = $(SIZE) -A $(OUTDIR)/$(TARGET).elf +##ELFSIZE = $(SIZE) --format=Berkeley --common $(OUTDIR)/$(TARGET).elf +sizebefore: +# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); echo; fi + +sizeafter: +# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); echo; fi + @echo $(MSG_SIZE_AFTER) + $(ELFSIZE) + +# Display compiler version information. +gccversion : + @$(CC) --version +# @echo $(ALLOBJ) + +# Program the device. +ifeq ($(USE_BOOTLOADER), YES) +# Program the device with OP Upload Tool". +program: $(OUTDIR)/$(TARGET).bin + @echo ${quote}Programming with OP Upload Tool${quote} + ../../ground/src/experimental/upload-build-desktop/debug/OPUploadTool -d 0 -p $(OUTDIR)/$(TARGET).bin +else +ifeq ($(FLASH_TOOL),OPENOCD) +# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script". +program: $(OUTDIR)/$(TARGET).elf + @echo ${quote}Programming with OPENOCD${quote} + $(OOCD_EXE) $(OOCD_CL) +endif +endif + +# Create final output file (.hex) from ELF output file. +%.hex: %.elf +## @echo + @echo $(MSG_LOAD_FILE) $@ + $(OBJCOPY) -O ihex $< $@ + +# Create final output file (.bin) from ELF output file. +%.bin: %.elf +## @echo + @echo $(MSG_LOAD_FILE) $@ + $(OBJCOPY) -O binary $< $@ + +# Create extended listing file/disassambly from ELF output file. +# using objdump testing: option -C +%.lss: %.elf +## @echo + @echo $(MSG_EXTENDED_LISTING) $@ + $(OBJDUMP) -h -S -C -r $< > $@ +# $(OBJDUMP) -x -S $< > $@ + +# Create a symbol table from ELF output file. +%.sym: %.elf +## @echo + @echo $(MSG_SYMBOL_TABLE) $@ + $(NM) -n $< > $@ + +# Link: create ELF output file from object files. +.SECONDARY : $(TARGET).elf +.PRECIOUS : $(ALLOBJ) +%.elf: $(ALLOBJ) + @echo $(MSG_LINKING) $@ +# use $(CC) for C-only projects or $(CPP) for C++-projects: + $(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) +# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) + + +# Assemble: create object files from assembler source files. +define ASSEMBLE_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_ASSEMBLING) $$< to $$@ + $(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@ +endef +$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) + +# Assemble: create object files from assembler source files. ARM-only +define ASSEMBLE_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_ASSEMBLING_ARM) $$< to $$@ + $(CC) -c $$(ASFLAGS) $$< -o $$@ +endef +$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) + + +# Compile: create object files from C source files. +define COMPILE_C_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILING) $$< to $$@ + $(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ +endef +$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) + +# Compile: create object files from C source files. ARM-only +define COMPILE_C_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILING_ARM) $$< to $$@ + $(CC) -c $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ +endef +$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) + + +# Compile: create object files from C++ source files. +define COMPILE_CPP_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILINGCPP) $$< to $$@ + $(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ +endef +$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) + +# Compile: create object files from C++ source files. ARM-only +define COMPILE_CPP_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILINGCPP_ARM) $$< to $$@ + $(CC) -c $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ +endef +$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) + + +# Compile: create assembler files from C source files. ARM/Thumb +$(SRC:.c=.s) : %.s : %.c + @echo $(MSG_ASMFROMC) $< to $@ + $(CC) $(THUMB) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ + +# Compile: create assembler files from C source files. ARM only +$(SRCARM:.c=.s) : %.s : %.c + @echo $(MSG_ASMFROMC_ARM) $< to $@ + $(CC) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ + +# Generate Doxygen documents +docs: + doxygen $(DOXYGENDIR)/doxygen.cfg + +# Target: clean project. +clean: begin clean_list finished end + +clean_list : +## @echo + @echo $(MSG_CLEANING) + $(REMOVE) $(OUTDIR)/$(TARGET).map + $(REMOVE) $(OUTDIR)/$(TARGET).elf + $(REMOVE) $(OUTDIR)/$(TARGET).hex + $(REMOVE) $(OUTDIR)/$(TARGET).bin + $(REMOVE) $(OUTDIR)/$(TARGET).sym + $(REMOVE) $(OUTDIR)/$(TARGET).lss + $(REMOVE) $(wildcard $(OUTDIR)/*.c) + $(REMOVE) $(wildcard $(OUTDIR)/*.h) + $(REMOVE) $(ALLOBJ) + $(REMOVE) $(LSTFILES) + $(REMOVE) $(DEPFILES) + $(REMOVE) $(SRC:.c=.s) + $(REMOVE) $(SRCARM:.c=.s) + $(REMOVE) $(CPPSRC:.cpp=.s) + $(REMOVE) $(CPPSRCARM:.cpp=.s) + + +# Create output files directory +# all known MS Windows OS define the ComSpec environment variable +ifdef ComSpec +$(shell md $(OUTDIR) 2>NUL) +else +$(shell mkdir $(OUTDIR) 2>/dev/null) +endif + +# Include the dependency files. +ifdef ComSpec +-include $(shell md $(OUTDIR)\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) +else +-include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) +endif + + + +# Listing of phony targets. +.PHONY : all begin finish end sizebefore sizeafter gccversion \ +build elf hex bin lss sym clean clean_list program gencode + From 2f7320fc16dd1c51765908952e4b863614b56fcb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 19 Mar 2011 19:58:57 -0500 Subject: [PATCH 229/543] Common Activity class that binds to the Telemetry service --- .../androidgcs/ObjectManagerActivity.java | 97 +++++++++++++++++++ 1 file changed, 97 insertions(+) create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java new file mode 100644 index 000000000..9f57796dc --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -0,0 +1,97 @@ +package org.openpilot.androidgcs; + +import org.openpilot.androidgcs.OPTelemetryService.LocalBinder; +import org.openpilot.androidgcs.OPTelemetryService.TelemTask; +import org.openpilot.uavtalk.UAVObjectManager; + +import android.app.Activity; +import android.content.BroadcastReceiver; +import android.content.ComponentName; +import android.content.Context; +import android.content.Intent; +import android.content.IntentFilter; +import android.content.ServiceConnection; +import android.os.Bundle; +import android.os.IBinder; +import android.util.Log; + +public abstract class ObjectManagerActivity extends Activity { + + private final String TAG = "ObjectManagerActivity"; + private static int LOGLEVEL = 2; +// private static boolean WARN = LOGLEVEL > 1; + private static boolean DEBUG = LOGLEVEL > 0; + + UAVObjectManager objMngr; + boolean mBound = false; + boolean mConnected = false; + LocalBinder binder; + + + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + + BroadcastReceiver connectedReceiver = new BroadcastReceiver() { + @Override + public void onReceive(Context context, Intent intent) { + Log.d(TAG, "Received intent"); + TelemTask task; + if(intent.getAction().compareTo(OPTelemetryService.INTENT_ACTION_CONNECTED) == 0) { + + if(binder == null) + return; + if((task = binder.getTelemTask(0)) == null) + return; + objMngr = task.getObjectManager(); + mConnected = true; + onOPConnected(); + Log.d(TAG, "Connected()"); + } else if (intent.getAction().compareTo(OPTelemetryService.INTENT_ACTION_DISCONNECTED) == 0) { + objMngr = null; + mConnected = false; + onOPDisconnected(); + Log.d(TAG, "Disonnected()"); + } + } + }; + + IntentFilter filter = new IntentFilter(); + filter.addCategory(OPTelemetryService.INTENT_CATEGORY_GCS); + filter.addAction(OPTelemetryService.INTENT_ACTION_CONNECTED); + filter.addAction(OPTelemetryService.INTENT_ACTION_DISCONNECTED); + registerReceiver(connectedReceiver, filter); + } + + void onOPConnected() { + + } + + void onOPDisconnected() { + + } + + @Override + public void onStart() { + super.onStart(); + Intent intent = new Intent(this, OPTelemetryService.class); + bindService(intent, mConnection, Context.BIND_AUTO_CREATE); + } + + /** Defines callbacks for service binding, passed to bindService() */ + private ServiceConnection mConnection = new ServiceConnection() { + public void onServiceConnected(ComponentName arg0, IBinder service) { + // We've bound to LocalService, cast the IBinder and attempt to open a connection + if (DEBUG) Log.d(TAG,"Service bound"); + binder = (LocalBinder) service; + binder.openFakeConnection(); + } + + public void onServiceDisconnected(ComponentName name) { + mBound = false; + mConnected = false; + objMngr = null; + } + }; +} From a70c967f9c4da5564b2e5e2957a4436b90d70b36 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 19 Mar 2011 20:00:12 -0500 Subject: [PATCH 230/543] Start of a widget for monitoring telemetry status --- androidgcs/AndroidManifest.xml | 43 +++++++++++++------ androidgcs/res/layout/telemetry_widget.xml | 7 +++ .../openpilot/androidgcs/TelemetryWidget.java | 31 +++++++++++++ 3 files changed, 67 insertions(+), 14 deletions(-) create mode 100644 androidgcs/res/layout/telemetry_widget.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 6c89f2632..9a3d1dd25 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -1,23 +1,38 @@ - + package="org.openpilot.androidgcs" android:versionCode="1" + android:versionName="1.0"> + - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + - + \ No newline at end of file diff --git a/androidgcs/res/layout/telemetry_widget.xml b/androidgcs/res/layout/telemetry_widget.xml new file mode 100644 index 000000000..6af378104 --- /dev/null +++ b/androidgcs/res/layout/telemetry_widget.xml @@ -0,0 +1,7 @@ + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java new file mode 100644 index 000000000..90ab80899 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java @@ -0,0 +1,31 @@ +package org.openpilot.androidgcs; + +import android.appwidget.AppWidgetManager; +import android.appwidget.AppWidgetProvider; +import android.content.Context; +import android.content.Intent; +import android.os.Bundle; +import android.widget.RemoteViews; + +public class TelemetryWidget extends AppWidgetProvider { + + private static boolean connected = false; + + public void onUpdate(Context context, AppWidgetManager appWidgetManager, int[] appWidgetIds) { + final int N = appWidgetIds.length; + + // Perform this loop procedure for each App Widget that belongs to this provider + for (int i=0; i Date: Sat, 19 Mar 2011 20:01:01 -0500 Subject: [PATCH 231/543] Get rid of lots of warnings --- .../androidgcs/OPTelemetryService.java | 211 ++++++++++++++---- .../openpilot/androidgcs/ObjectBrowser.java | 83 ++----- .../openpilot/androidgcs/TelemetryWidget.java | 4 - .../src/org/openpilot/uavtalk/Telemetry.java | 1 - .../openpilot/uavtalk/TelemetryMonitor.java | 11 +- .../src/org/openpilot/uavtalk/UAVObject.java | 2 +- .../org/openpilot/uavtalk/UAVObjectField.java | 11 +- 7 files changed, 194 insertions(+), 129 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 5a48bbc05..557c3b256 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -2,6 +2,7 @@ package org.openpilot.androidgcs; import org.openpilot.uavtalk.Telemetry; import org.openpilot.uavtalk.TelemetryMonitor; +import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; @@ -13,69 +14,192 @@ import android.app.Service; import android.content.Context; import android.content.Intent; import android.net.Uri; +import android.os.Binder; import android.os.Handler; +import android.os.HandlerThread; import android.os.IBinder; import android.os.Looper; +import android.os.Message; +import android.os.Process; import android.util.Log; +import android.widget.Toast; public class OPTelemetryService extends Service { + + // Logging settings private final String TAG = "OPTElemetryService"; public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; - final int DISCONNECT_MESSAGE = 0; - final int CONNECT_MESSAGE = 1; - final int CONNECT_FAILED_MESSAGE = 2; - - private UAVObjectManager objMngr; - private UAVTalk uavTalk; - private Telemetry tel; - private TelemetryMonitor mon; - - private Handler handler; + // Intent category + public final static String INTENT_CATEGORY_GCS = "org.openpilot.intent.category.GCS"; - @Override - public IBinder onBind(Intent arg0) { - return null; - } + // Intent actions + public final static String INTENT_ACTION_CONNECTED = "org.openpilot.intent.action.CONNECTED"; + public final static String INTENT_ACTION_DISCONNECTED = "org.openpilot.intent.action.DISCONNECTED"; + + // Variables for local message handler thread + private Looper mServiceLooper; + private ServiceHandler mServiceHandler; + + // Message ids + final int MSG_START = 0; + final int MSG_CONNECT_BT = 1; + final int MSG_CONNECT_FAKE = 2; + final int MSG_TOAST = 100; + + private Thread activeTelem; + + private final IBinder mBinder = new LocalBinder(); + + private final class ServiceHandler extends Handler { + public ServiceHandler(Looper looper) { + super(looper); + } + @Override + public void handleMessage(Message msg) { + switch(msg.arg1) { + case MSG_START: + Toast.makeText(OPTelemetryService.this, "HERE", Toast.LENGTH_SHORT); + System.out.println("HERE"); + stopSelf(msg.arg2); + case MSG_CONNECT_BT: + activeTelem = new BTTelemetryThread(); + activeTelem.start(); + break; + case MSG_CONNECT_FAKE: + activeTelem = new FakeTelemetryThread(); + activeTelem.start(); + break; + case MSG_TOAST: + Toast.makeText(OPTelemetryService.this, (String) msg.obj, Toast.LENGTH_SHORT); + break; + default: + System.out.println(msg.toString()); + throw new Error("Invalid message"); + } + } + }; @Override public void onCreate() { - super.onCreate(); - - if (DEBUG) Log.d(TAG, "Telemetry Service started"); + // Low priority thread for message handling with service + HandlerThread thread = new HandlerThread("TelemetryServiceHandler", + Process.THREAD_PRIORITY_BACKGROUND); + thread.start(); - Thread telemetryThread = new Thread(telemetryRunnable); - telemetryThread.start(); - } + // Get the HandlerThread's Looper and use it for our Handler + mServiceLooper = thread.getLooper(); + mServiceHandler = new ServiceHandler(mServiceLooper); + } + + @Override + public int onStartCommand(Intent intent, int flags, int startId) { + Toast.makeText(this, "Telemetry service starting", Toast.LENGTH_SHORT).show(); + + System.out.println("Start"); + // For each start request, send a message to start a job and deliver the + // start ID so we know which request we're stopping when we finish the job + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_START; + msg.arg2 = startId; + mServiceHandler.sendMessage(msg); + + // If we get killed, after returning from here, restart + return START_STICKY; + } + + @Override + public IBinder onBind(Intent intent) { + return mBinder; + } @Override public void onDestroy() { - super.onDestroy(); + Toast.makeText(this, "Telemetry service done", Toast.LENGTH_SHORT).show(); } + + public class LocalBinder extends Binder { + public TelemTask getTelemTask(int id) { + return (TelemTask) activeTelem; + } + public void openFakeConnection() { + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_CONNECT_FAKE; + mServiceHandler.sendMessage(msg); + } + }; - private final Runnable telemetryRunnable = new Runnable() { + public void toastMessage(String msgText) { + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_TOAST; + msg.obj = msgText; + mServiceHandler.sendMessage(msg); + } + + public interface TelemTask { + public UAVObjectManager getObjectManager(); + }; + + // Fake class for testing, simply emits periodic updates on + private class FakeTelemetryThread extends Thread implements TelemTask { + private UAVObjectManager objMngr; + public UAVObjectManager getObjectManager() { return objMngr; }; + + FakeTelemetryThread() { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + } + + public void run() { + System.out.println("Runnin fake thread"); + + Intent intent = new Intent(); + intent.setAction(INTENT_ACTION_CONNECTED); + sendBroadcast(intent,null); + + //toastMessage("Started fake telemetry thread"); + UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); + while(true) { + systemStats.updated(); + try { + Thread.sleep(1000); + } catch (InterruptedException e) { + break; + } + } + } + } + private class BTTelemetryThread extends Thread implements TelemTask { + + private UAVObjectManager objMngr; + private UAVTalk uavTalk; + private Telemetry tel; + //private TelemetryMonitor mon; + + public UAVObjectManager getObjectManager() { return objMngr; }; + + BTTelemetryThread() { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + } public void run() { if (DEBUG) Log.d(TAG, "Telemetry Thread started"); Looper.prepare(); - - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); - - postNotification(CONNECT_FAILED_MESSAGE, "Connecting"); + BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this, BluetoothUAVTalk.DEVICE_NAME); for( int i = 0; i < 10; i++ ) { if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); - + bt.connect(objMngr); - + if (DEBUG) Log.d(TAG, "Done attempting connection"); if( bt.getConnected() ) break; - + try { Thread.sleep(1000); } catch (InterruptedException e) { @@ -85,17 +209,15 @@ public class OPTelemetryService extends Service { } } if( ! bt.getConnected() ) { - postNotification(CONNECT_FAILED_MESSAGE, "Could not connect to UAV"); return; } - - postNotification(CONNECT_MESSAGE, "Connected to UAV port"); - + + if (DEBUG) Log.d(TAG, "Connected via bluetooth"); - + uavTalk = bt.getUavtalk(); tel = new Telemetry(uavTalk, objMngr); - mon = new TelemetryMonitor(objMngr,tel); + new TelemetryMonitor(objMngr,tel); if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); while(true) { @@ -103,30 +225,23 @@ public class OPTelemetryService extends Service { break; } if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); - postNotification(DISCONNECT_MESSAGE,"UAVTalk stream disconnected"); } - + }; - + void postNotification(int id, String message) { String ns = Context.NOTIFICATION_SERVICE; NotificationManager mNManager = (NotificationManager) getSystemService(ns); final Notification msg = new Notification(R.drawable.icon, message, System.currentTimeMillis()); - + Context context = getApplicationContext(); CharSequence contentTitle = "OpenPilot"; CharSequence contentText = message; Intent msgIntent = new Intent(Intent.ACTION_VIEW, Uri.parse("http://forums.openpilot.org")); PendingIntent intent = PendingIntent.getActivity(this, 0, msgIntent, Intent.FLAG_ACTIVITY_NEW_TASK); - + msg.setLatestEventInfo(context, contentTitle, contentText, intent); - + mNManager.notify(id, msg); } - - public UAVObjectManager getObjMngr() { return objMngr; }; - public UAVTalk getUavTalk() { return uavTalk; }; - public Telemetry getTelemetry() { return tel; }; - public TelemetryMonitor getTelemetryMonitor() { return mon; }; - } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index 6bb217930..48aa1cd10 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -1,42 +1,21 @@ package org.openpilot.androidgcs; -import java.io.IOException; import java.util.Observable; import java.util.Observer; -import java.util.Set; -import java.util.UUID; -import android.app.Activity; -import android.bluetooth.BluetoothAdapter; -import android.bluetooth.BluetoothDevice; -import android.bluetooth.BluetoothSocket; -import android.content.Intent; import android.os.Bundle; import android.os.Handler; import android.util.Log; import android.widget.TextView; import android.widget.ToggleButton; -import org.openpilot.androidgcs.*; -import org.openpilot.uavtalk.Telemetry; -import org.openpilot.uavtalk.TelemetryMonitor; import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVTalk; -import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; -public class ObjectBrowser extends Activity { - +public class ObjectBrowser extends ObjectManagerActivity { + private final String TAG = "ObjectBrower"; - private final String DEVICE_NAME = "RN42-222D"; - private final int REQUEST_ENABLE_BT = 0; - private UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); - BluetoothAdapter mBluetoothAdapter; - BluetoothSocket socket; boolean connected; - UAVObjectManager objMngr; - UAVTalk uavTalk; - + final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { public void run() { @@ -44,9 +23,9 @@ public class ObjectBrowser extends Activity { button.setChecked(!connected); Log.d(TAG,"HERE" + connected); - + TextView text = (TextView) findViewById(R.id.textView1); - + UAVObject obj1 = objMngr.getObject("SystemStats"); UAVObject obj2 = objMngr.getObject("AttitudeRaw"); UAVObject obj3 = objMngr.getObject("AttitudeActual"); @@ -57,52 +36,30 @@ public class ObjectBrowser extends Activity { Log.d(TAG,"And here"); text.setText(obj1.toString() + "\n" + obj2.toString() + "\n" + obj3.toString() + "\n" + obj4.toString() ); - + } }; - - /** Called when the activity is first created. */ - @Override - public void onCreate(Bundle savedInstanceState) { - super.onCreate(savedInstanceState); - setContentView(R.layout.main); - - Log.d(TAG, "Launching Object Browser"); - Log.d(TAG, "Start OP Telemetry Service"); - startService( new Intent( this, OPTelemetryService.class ) ); - - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.main); + } + + @Override + void onOPConnected() { + // Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); + Log.d(TAG, "onOPConnected()"); UAVObject obj = objMngr.getObject("SystemStats"); + Log.d(TAG, ((Boolean) (obj == null)).toString()); if(obj != null) obj.addUpdatedObserver(new Observer() { public void update(Observable observable, Object data) { uavobjHandler.post(updateText); } }); - obj = objMngr.getObject("AttitudeRaw"); - if(obj != null) - obj.addUpdatedObserver(new Observer() { - public void update(Observable observable, Object data) { - uavobjHandler.post(updateText); - } - }); - obj = objMngr.getObject("AttitudeActual"); - if(obj != null) - obj.addUpdatedObserver(new Observer() { - public void update(Observable observable, Object data) { - uavobjHandler.post(updateText); - } - }); - obj = objMngr.getObject("SystemAlarms"); - if(obj != null) - obj.addUpdatedObserver(new Observer() { - public void update(Observable observable, Object data) { - uavobjHandler.post(updateText); - } - }); - } - + + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java index 90ab80899..d316526ef 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java +++ b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java @@ -3,14 +3,10 @@ package org.openpilot.androidgcs; import android.appwidget.AppWidgetManager; import android.appwidget.AppWidgetProvider; import android.content.Context; -import android.content.Intent; -import android.os.Bundle; import android.widget.RemoteViews; public class TelemetryWidget extends AppWidgetProvider { - private static boolean connected = false; - public void onUpdate(Context context, AppWidgetManager appWidgetManager, int[] appWidgetIds) { final int N = appWidgetIds.length; diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index c754c8329..1395a5c08 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -630,7 +630,6 @@ public class Telemetry { /** * Private variables */ - private TelemetryStats stats; private UAVObjectManager objMngr; private UAVTalk utalk; private UAVObject gcsStatsObj; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 9b4474d8e..7208181ad 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -8,9 +8,6 @@ import java.util.Observer; import java.util.Timer; import java.util.TimerTask; -import org.openpilot.uavtalk.uavobjects.FlightTelemetryStats; -import org.openpilot.uavtalk.uavobjects.GCSTelemetryStats; - import android.util.Log; public class TelemetryMonitor { @@ -26,7 +23,7 @@ public class TelemetryMonitor { private UAVObjectManager objMngr; private Telemetry tel; - private UAVObject objPending; +// private UAVObject objPending; private UAVObject gcsStatsObj; private UAVObject flightStatsObj; private Timer periodicTask; @@ -38,7 +35,7 @@ public class TelemetryMonitor { { this.objMngr = objMngr; this.tel = tel; - this.objPending = null; +// this.objPending = null; queue = new ArrayList(); // Get stats objects @@ -142,7 +139,7 @@ public class TelemetryMonitor { // Request update tel.updateRequested(obj); - objPending = obj; +// objPending = obj; } /** @@ -155,7 +152,7 @@ public class TelemetryMonitor { if (DEBUG) Log.d(TAG,"transactionCompleted. Status: " + success); // TODO: Need to be able to disconnect signals //obj->disconnect(this); - objPending = null; +// objPending = null; if(!success) { Log.e(TAG, "Transaction failed: " + obj.getName() + " sending again."); diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index ba3bf1ae3..940b076a5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -64,7 +64,7 @@ public abstract class UAVObject { if(manually) updatedManual(); } - void updated() { updated(true); }; + public void updated() { updated(true); }; private CallbackListener unpackedListeners = new CallbackListener(this); public void addUnpackedObserver(Observer o) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index de2059e90..78ad70630 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -1,6 +1,5 @@ package org.openpilot.uavtalk; -import java.io.Serializable; import java.nio.ByteBuffer; import java.nio.ByteOrder; import java.util.ArrayList; @@ -91,7 +90,8 @@ public class UAVObjectField { * @param dataOut * @return the number of bytes added **/ - public synchronized int pack(ByteBuffer dataOut) { + @SuppressWarnings("unchecked") + public synchronized int pack(ByteBuffer dataOut) { // Pack each element in output buffer dataOut.order(ByteOrder.LITTLE_ENDIAN); switch (type) @@ -152,7 +152,8 @@ public class UAVObjectField { return getNumBytes(); } - public synchronized int unpack(ByteBuffer dataIn) { + @SuppressWarnings("unchecked") + public synchronized int unpack(ByteBuffer dataIn) { // Unpack each element from input buffer dataIn.order(ByteOrder.LITTLE_ENDIAN); switch (type) @@ -436,9 +437,9 @@ public class UAVObjectField { } } - public String toString() { + public String toString() { String sout = new String(); - sout += name + ": " + ((List) data).toString() + " (" + units + ")\n"; + sout += name + ": " + data.toString() + " (" + units + ")\n"; return sout; } From 6613e4d3bf2eb381998ddb1d6b64bc29d5797271 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 20 Mar 2011 06:09:06 -0500 Subject: [PATCH 232/543] Added some missing files. Improved object browser to use ListView. ExpandableListView next. --- androidgcs/Doc/.AndroidArchitecture.txt.swp | Bin 0 -> 12288 bytes androidgcs/Doc/AndroidArchitecture.txt | 31 +++++++ androidgcs/res/layout/main.xml | 17 ++-- androidgcs/res/layout/object_view.xml | 7 ++ androidgcs/res/menu/options_menu.xml | 6 ++ androidgcs/res/values/strings.xml | 4 + androidgcs/res/xml/telemetry_widget_info.xml | 9 ++ .../androidgcs/OPTelemetryService.java | 69 +++++++++++--- .../openpilot/androidgcs/ObjectBrowser.java | 84 +++++++++++++----- .../androidgcs/ObjectManagerActivity.java | 1 - .../openpilot/uavtalk/TelemetryMonitor.java | 30 +++++-- .../src/org/openpilot/uavtalk/UAVTalk.java | 3 +- 12 files changed, 202 insertions(+), 59 deletions(-) create mode 100644 androidgcs/Doc/.AndroidArchitecture.txt.swp create mode 100644 androidgcs/Doc/AndroidArchitecture.txt create mode 100644 androidgcs/res/layout/object_view.xml create mode 100644 androidgcs/res/menu/options_menu.xml create mode 100644 androidgcs/res/xml/telemetry_widget_info.xml diff --git a/androidgcs/Doc/.AndroidArchitecture.txt.swp b/androidgcs/Doc/.AndroidArchitecture.txt.swp new file mode 100644 index 0000000000000000000000000000000000000000..167a072526a8207b396d71d6dd7d3e7a417cba19 GIT binary patch literal 12288 zcmeHNzmFS56rMwnA3z`iK>^J`id>>QJ0S%T4RS8dVU#03?7Kh}jd#cP-0jXRGqdLy zB_JeP;2%IhK?4;OL^LQ=G-;^`1>rxSqu_h9yY}UZv?yp!`Qr2bn0fDe-}~N1+2N_J z-UffYb%x>RC}UrI^6`eazqIt*H;ip3#(SgBo~CmT`FUIA`E0F~nM7m{xr}`{U$A}N zBxNqOckRp8jIGFXrN`|{h18c-W_(-d)EbqJ6GxY}JJr{YO(x3A#FtjK{0;xG&EmPp zKxAOSK2dF}KmI(Y2WSNQYKZ7$Bo-y#E%fyh8)ATkgchzvvqA_I|u|2+e~ zSYjU`%g5?WFVvq)`#$Th@gp)28Hfx-1|kEIfyh8)ATkgchzvvqA_I|uN00%LGPe3S zW8w(}kN^K~{{8>wvy6QWdgNH7@GiVz&YUWBaGb!egqV740sWE0XPKw z{4`@0=mO_~lfb>F82cRP0!M*ofjdt!whJr+$AP~NGj<=i3)}=&fZq=>_6u+am;%ed z%fL&(-Ghw%0DKSJ0&W6r;2>}SxP5@J?|^TC1b7#?2Al(q0{?)6KY)9{ufSKpm%uIH zCJ;D!1Zx~ajtoQw{v!rDLzO8%3N*zup~i9E8`N zJjt(=($1ROmC@XJ;Y%0Jt%)q-ixtDMb+s$`1g~IalEU^A$uAAJvEPQ!Vk~WlMhc{| z+1bJ!d>}KKOOH)@=af#RWz3aDVXT*Fi}iSFw8t_^?}Wu_0x0t`OR*ESqfJcV5uM{= zXiCqg6IJbi16DEy2JlW;QP7eDT)l4K9sH7M5==$7f5Rz69N4eGEt)$7oa0aK>dR<<+V;*EZhkKkq=f0;#uJWRh7h|Lk)@Mia*XtyY#&& zZ&P+!eJnl81(K?`_p@bp0t|FA4-tfozxuZv%GMYV5G@j`J6 zy5|AVh8{o$Lu5PWw$TtDS(68fK+`@G=y$Jf_13zT3-nFZvp2l7T4daWb|zs;NP;A2 z<(RC7`h?s^4AJ|}YlBe!Esc)S*+4( zVXz0Jx=DhbcZh^O(6Wiip%Xq8!7NiU9#D!uWPYRr+*Jk6mt6^O5H9GbdN-7=fY?G2 zKqZt<w>-1wnI&T9)>r`IggCxCM`qiRMFH(r;p=PLhmUW2tq;~>J3K{ zE@~y3gMwQW(#?=$4srAA~;j1tIlNGZG^8G*3NuIRz$>-_K0|9#2o7)E zy0$aPj`Sd1^D6_g-Fh==!;D$w8{K}tv)<*GJN z%~W%*a@k^KkwQ03=yfqrhy(^WMiQ{XP&Dw5tf{9ObFD)iG$zf~s?3mXt&3{yFhFYt zLUMI{W)!}SFonYu2;1PDnASejO27?lH&?XqC1*CKB2< zJRd2H4ssgICx|G+fTt48MX*tgmL`RI(p33h$kce^=a=@Oe8i7VUSI1!c$Bh$@MKO} z)yAt)QxAH8;9x{Ma{lmmg0?`p(M<5NMIcQCRwfb;P%hM!HY3^6{aAa>5fmB5hHtb? zVZnXGHoT4&hb!U1?v2pE^H6zZEvPGvF2pr&X_;cKVK49(?j|=txdk7|DGdht+4F>0 I9l+o0U$ht(TmS$7 literal 0 HcmV?d00001 diff --git a/androidgcs/Doc/AndroidArchitecture.txt b/androidgcs/Doc/AndroidArchitecture.txt new file mode 100644 index 000000000..d9cdf2ada --- /dev/null +++ b/androidgcs/Doc/AndroidArchitecture.txt @@ -0,0 +1,31 @@ +------- TELEMETRY --------- +The Telemetry system has been implemented, and is composed of a few +major components: + +Telemetry.java - receives command to transmit objects through telemetry and +also emits notification when transactions are completed + +TelemetryMonitor.java - monitors the FlightTelemetryStats and GCSTelemetryStats +to establish when a working connection is in place. Also initiates downloading +all the objects on a new connection. + +UAVObjectManager.java - the central data store. The data is actually stored +within objects, but this maintains the handles to all of them. + +UAVTalk.java - the actual communication layer. Can packetize an object and +insert into stream and process the incoming stream and update objects +accordingly. + +---- MESSAGE PASSING ---- +The current implementation/analog to the slots/sockets in QT are Observers +which are registered as added to an Observable. This is used extensibly within +the telemetry system. I will continue to use this _within_ the Telemetry +module so it doesn't depend on any android features. + +In android there is a constraint that UI operations should all be done from the +UI thread. The most common way to do this is for the UI object (such as +Activity) to instantiate a Handler to which messages or runnables are posted. + +So for external objects they will register a runnable somehow... + + diff --git a/androidgcs/res/layout/main.xml b/androidgcs/res/layout/main.xml index 9e5f90add..880e276ff 100644 --- a/androidgcs/res/layout/main.xml +++ b/androidgcs/res/layout/main.xml @@ -1,13 +1,6 @@ - - - - - + + + diff --git a/androidgcs/res/layout/object_view.xml b/androidgcs/res/layout/object_view.xml new file mode 100644 index 000000000..fdf5a0bae --- /dev/null +++ b/androidgcs/res/layout/object_view.xml @@ -0,0 +1,7 @@ + + + diff --git a/androidgcs/res/menu/options_menu.xml b/androidgcs/res/menu/options_menu.xml new file mode 100644 index 000000000..db86aa670 --- /dev/null +++ b/androidgcs/res/menu/options_menu.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 52fa56534..8daa0ec36 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,4 +1,8 @@ OpenPilot GCS + Settings + Connect + Disconnect + OpenPilot Object Browser diff --git a/androidgcs/res/xml/telemetry_widget_info.xml b/androidgcs/res/xml/telemetry_widget_info.xml new file mode 100644 index 000000000..f2ced6645 --- /dev/null +++ b/androidgcs/res/xml/telemetry_widget_info.xml @@ -0,0 +1,9 @@ + + + android:minWidth="294dp" + android:minHeight="72dp" + android:updatePeriodMillis="86400000" + android:initialLayout="@layout/telemetry_widget"> + + diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 557c3b256..7b3030d4f 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -1,5 +1,8 @@ package org.openpilot.androidgcs; +import java.util.Observable; +import java.util.Observer; + import org.openpilot.uavtalk.Telemetry; import org.openpilot.uavtalk.TelemetryMonitor; import org.openpilot.uavtalk.UAVDataObject; @@ -27,7 +30,7 @@ import android.widget.Toast; public class OPTelemetryService extends Service { // Logging settings - private final String TAG = "OPTElemetryService"; + private final String TAG = "OPTelemetryService"; public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -44,10 +47,13 @@ public class OPTelemetryService extends Service { private ServiceHandler mServiceHandler; // Message ids - final int MSG_START = 0; - final int MSG_CONNECT_BT = 1; - final int MSG_CONNECT_FAKE = 2; - final int MSG_TOAST = 100; + static final int MSG_START = 0; + static final int MSG_CONNECT_BT = 1; + static final int MSG_CONNECT_FAKE = 2; + static final int MSG_DISCONNECT = 3; + static final int MSG_TOAST = 100; + + private boolean terminate = false; private Thread activeTelem; @@ -65,12 +71,28 @@ public class OPTelemetryService extends Service { System.out.println("HERE"); stopSelf(msg.arg2); case MSG_CONNECT_BT: + terminate = false; activeTelem = new BTTelemetryThread(); activeTelem.start(); break; case MSG_CONNECT_FAKE: + terminate = false; activeTelem = new FakeTelemetryThread(); activeTelem.start(); + break; + case MSG_DISCONNECT: + terminate = true; + try { + activeTelem.join(); + } catch (InterruptedException e) { + e.printStackTrace(); + } + activeTelem = null; + + Intent intent = new Intent(); + intent.setAction(INTENT_ACTION_DISCONNECTED); + sendBroadcast(intent,null); + break; case MSG_TOAST: Toast.makeText(OPTelemetryService.this, (String) msg.obj, Toast.LENGTH_SHORT); @@ -129,8 +151,18 @@ public class OPTelemetryService extends Service { msg.arg1 = MSG_CONNECT_FAKE; mServiceHandler.sendMessage(msg); } + public void openBTConnection() { + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_CONNECT_BT; + mServiceHandler.sendMessage(msg); + } + public void stopConnection() { + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_DISCONNECT; + mServiceHandler.sendMessage(msg); + } }; - + public void toastMessage(String msgText) { Message msg = mServiceHandler.obtainMessage(); msg.arg1 = MSG_TOAST; @@ -151,17 +183,17 @@ public class OPTelemetryService extends Service { objMngr = new UAVObjectManager(); UAVObjectsInitialize.register(objMngr); } - + public void run() { - System.out.println("Runnin fake thread"); + System.out.println("Running fake thread"); Intent intent = new Intent(); intent.setAction(INTENT_ACTION_CONNECTED); sendBroadcast(intent,null); - + //toastMessage("Started fake telemetry thread"); UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); - while(true) { + while( !terminate ) { systemStats.updated(); try { Thread.sleep(1000); @@ -176,7 +208,7 @@ public class OPTelemetryService extends Service { private UAVObjectManager objMngr; private UAVTalk uavTalk; private Telemetry tel; - //private TelemetryMonitor mon; + private TelemetryMonitor mon; public UAVObjectManager getObjectManager() { return objMngr; }; @@ -217,10 +249,21 @@ public class OPTelemetryService extends Service { uavTalk = bt.getUavtalk(); tel = new Telemetry(uavTalk, objMngr); - new TelemetryMonitor(objMngr,tel); + mon = new TelemetryMonitor(objMngr,tel); + mon.addObserver(new Observer() { + public void update(Observable arg0, Object arg1) { + System.out.println("Mon updated. Connected: " + mon.getConnected() + " objects updated: " + mon.getObjectsUpdated()); + if(mon.getConnected() /*&& mon.getObjectsUpdated()*/) { + Intent intent = new Intent(); + intent.setAction(INTENT_ACTION_CONNECTED); + sendBroadcast(intent,null); + } + } + }); + if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); - while(true) { + while( !terminate ) { if( !uavTalk.processInputStream() ) break; } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index 48aa1cd10..f68e839c1 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -1,42 +1,67 @@ package org.openpilot.androidgcs; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; import java.util.Observable; import java.util.Observer; +import android.database.DataSetObserver; import android.os.Bundle; import android.os.Handler; import android.util.Log; +import android.view.Menu; +import android.view.MenuInflater; +import android.view.MenuItem; +import android.view.View; +import android.view.ViewGroup; +import android.widget.ArrayAdapter; +import android.widget.ExpandableListAdapter; +import android.widget.ExpandableListView; +import android.widget.ListView; +import android.widget.SimpleAdapter; +import android.widget.SimpleExpandableListAdapter; import android.widget.TextView; -import android.widget.ToggleButton; +import android.widget.Toast; +import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObject; public class ObjectBrowser extends ObjectManagerActivity { + @Override + public boolean onOptionsItemSelected(MenuItem item) { + switch(item.getItemId()) { + case R.id.menu_connect: + binder.openBTConnection(); + return true; + case R.id.menu_disconnect: + binder.stopConnection(); + updateText.run(); + return true; + case R.id.menu_settings: + return true; + default: + return super.onOptionsItemSelected(item); + } + + } + + @Override + public boolean onCreateOptionsMenu(Menu menu) { + MenuInflater inflater = getMenuInflater(); + inflater.inflate(R.menu.options_menu, menu); + return true; + } + private final String TAG = "ObjectBrower"; boolean connected; final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { public void run() { - ToggleButton button = (ToggleButton) findViewById(R.id.toggleButton1); - button.setChecked(!connected); - - Log.d(TAG,"HERE" + connected); - - TextView text = (TextView) findViewById(R.id.textView1); - - UAVObject obj1 = objMngr.getObject("SystemStats"); - UAVObject obj2 = objMngr.getObject("AttitudeRaw"); - UAVObject obj3 = objMngr.getObject("AttitudeActual"); - UAVObject obj4 = objMngr.getObject("SystemAlarms"); - - if(obj1 == null || obj2 == null || obj3 == null || obj4 == null) - return; - - Log.d(TAG,"And here"); - text.setText(obj1.toString() + "\n" + obj2.toString() + "\n" + obj3.toString() + "\n" + obj4.toString() ); - + Log.d(TAG,"Update"); + update(); } }; @@ -44,16 +69,15 @@ public class ObjectBrowser extends ObjectManagerActivity { @Override public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); - setContentView(R.layout.main); + setContentView(R.layout.main); } @Override void onOPConnected() { - // Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); + Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); Log.d(TAG, "onOPConnected()"); - + UAVObject obj = objMngr.getObject("SystemStats"); - Log.d(TAG, ((Boolean) (obj == null)).toString()); if(obj != null) obj.addUpdatedObserver(new Observer() { public void update(Observable observable, Object data) { @@ -62,4 +86,18 @@ public class ObjectBrowser extends ObjectManagerActivity { }); } + + public void update() { + List> allobjects = objMngr.getDataObjects(); + List linearized = new ArrayList(); + ListIterator> li = allobjects.listIterator(); + while(li.hasNext()) { + linearized.addAll(li.next()); + } + + ArrayAdapter adapter = new ArrayAdapter(this,R.layout.object_view, linearized); + ListView objects = (ListView) findViewById(R.id.object_list); + objects.setAdapter(adapter); + + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java index 9f57796dc..12a072de7 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -85,7 +85,6 @@ public abstract class ObjectManagerActivity extends Activity { // We've bound to LocalService, cast the IBinder and attempt to open a connection if (DEBUG) Log.d(TAG,"Service bound"); binder = (LocalBinder) service; - binder.openFakeConnection(); } public void onServiceDisconnected(ComponentName name) { diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 7208181ad..daedcc85b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -10,10 +10,10 @@ import java.util.TimerTask; import android.util.Log; -public class TelemetryMonitor { +public class TelemetryMonitor extends Observable{ private static final String TAG = "TelemetryMonitor"; - public static int LOGLEVEL = 0; + public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -31,6 +31,12 @@ public class TelemetryMonitor { private long lastUpdateTime; private List queue; + private boolean connected = false; + private boolean objects_updated = false; + + public boolean getConnected() { return connected; }; + public boolean getObjectsUpdated() { return objects_updated; }; + public TelemetryMonitor(UAVObjectManager objMngr, Telemetry tel) { this.objMngr = objMngr; @@ -116,8 +122,9 @@ public class TelemetryMonitor { if ( queue.isEmpty() ) { if (DEBUG) Log.d(TAG, "All objects retrieved: Connected Successfully"); - //qxtLog->debug("Object retrieval completed"); - //emit connected(); + objects_updated = true; + setChanged(); + notifyObservers(); return; } // Get next object from the queue @@ -260,9 +267,9 @@ public class TelemetryMonitor { // Force telemetry update if not yet connected boolean gcsStatusChanged = !oldStatus.equals(statusField.getValue()); - boolean gcsConnected = ((String) statusField.getValue()).compareTo("Connected") == 0; - boolean gcsDisconnected = ((String) statusField.getValue()).compareTo("Disconnected") == 0; - boolean flightConnected = ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0; + boolean gcsConnected = statusField.getValue().equals("Connected"); + boolean gcsDisconnected = statusField.getValue().equals("Disconnected"); + boolean flightConnected = flightStatsObj.getField("Status").equals("Connected"); if ( !gcsConnected || !flightConnected ) { @@ -275,14 +282,21 @@ public class TelemetryMonitor { { if (DEBUG) Log.d(TAG,"Connection with the autopilot established"); setPeriod(STATS_UPDATE_PERIOD_MS); + connected = true; + objects_updated = false; startRetrievingObjects(); + setChanged(); } if (gcsDisconnected && gcsStatusChanged) { if (DEBUG) Log.d(TAG,"Trying to connect to the autopilot"); setPeriod(STATS_CONNECT_PERIOD_MS); - //emit disconnected(); + connected = false; + objects_updated = false; + setChanged(); } + notifyObservers(); + } private void setPeriod(int ms) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 8671cdef9..39c1f6ee7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -197,8 +197,7 @@ public class UAVTalk extends Observable { return false; } - // System.out.println("Received byte " + val + " in state + " + - // rxState); + //System.out.println("Received byte " + val + " in state + " + rxState); processInputByte(val); return true; } From 247d3a7754ac5b48a0af2ce6ee91a483cdc5e91d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 20 Mar 2011 21:34:03 -0500 Subject: [PATCH 233/543] Added a home page, added an option to select connection type. Made the ListView adapter trigger updates on the data. --- androidgcs/AndroidManifest.xml | 8 ++- androidgcs/Doc/AndroidArchitecture.txt | 39 +++++++++++ androidgcs/res/layout/gcs_home.xml | 7 ++ androidgcs/res/values/arrays.xml | 15 +++++ androidgcs/res/values/strings.xml | 9 ++- androidgcs/res/xml/preferences.xml | 12 ++++ .../org/openpilot/androidgcs/HomePage.java | 23 +++++++ .../androidgcs/OPTelemetryService.java | 39 ++++++----- .../openpilot/androidgcs/ObjectBrowser.java | 65 ++++++++----------- .../androidgcs/ObjectManagerActivity.java | 28 ++++++++ .../org/openpilot/androidgcs/Preferences.java | 12 ++++ 11 files changed, 201 insertions(+), 56 deletions(-) create mode 100644 androidgcs/res/layout/gcs_home.xml create mode 100644 androidgcs/res/values/arrays.xml create mode 100644 androidgcs/res/xml/preferences.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/HomePage.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/Preferences.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 9a3d1dd25..a791d0fbb 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -10,17 +10,23 @@ - + + + + + + + diff --git a/androidgcs/Doc/AndroidArchitecture.txt b/androidgcs/Doc/AndroidArchitecture.txt index d9cdf2ada..0a17a8dfa 100644 --- a/androidgcs/Doc/AndroidArchitecture.txt +++ b/androidgcs/Doc/AndroidArchitecture.txt @@ -16,6 +16,11 @@ UAVTalk.java - the actual communication layer. Can packetize an object and insert into stream and process the incoming stream and update objects accordingly. +** Threading +Currently object updates run within the thread of the function that called +update. This should be changed so that it adds a message to the Telemetry +thread which will then send on its own time. + ---- MESSAGE PASSING ---- The current implementation/analog to the slots/sockets in QT are Observers which are registered as added to an Observable. This is used extensibly within @@ -28,4 +33,38 @@ Activity) to instantiate a Handler to which messages or runnables are posted. So for external objects they will register a runnable somehow... +--- TELEMETRY SERVICE --- +The telemetry connection will be maintained by a service separate from the the +main activity(s). Although it is a bit unusual, the service will support being +started and stopped, as well as being bound. Binding will be required to get +access to the Object Manager. +In addition, to make it forward looking, the start intent can specify a +connection to open. This will allow the service in future to monitor multiple +connections. + +The service will destroy itself only when all active connections disappear and +all activies are unbound. + +It will also handle any logging desired (I think). + +There will be a primary message handler thread. This thread will separately +launch telemetry threads when required. + +The service should send broadcast intents whenever a connection is estabilished +or dropped. + +I dont think the service should have the options about which UAVs are +supported. + +** Telemetry IBinder +*** Give handle to the ObjectManager for each UAV +*** Call disconnect +*** Query conncetion status + +--- TELEMETRY WIDGET --- +Listens for conncet/disconnect intents + +Also show if service is running? + +Ability to launch service? diff --git a/androidgcs/res/layout/gcs_home.xml b/androidgcs/res/layout/gcs_home.xml new file mode 100644 index 000000000..e6f4ea567 --- /dev/null +++ b/androidgcs/res/layout/gcs_home.xml @@ -0,0 +1,7 @@ + + + + diff --git a/androidgcs/res/values/arrays.xml b/androidgcs/res/values/arrays.xml new file mode 100644 index 000000000..18ee52298 --- /dev/null +++ b/androidgcs/res/values/arrays.xml @@ -0,0 +1,15 @@ + + + + None + Fake + Bluetooth + Network + + + 0 + 1 + 2 + 3 + + \ No newline at end of file diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 8daa0ec36..e9b66a312 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,8 +1,13 @@ - OpenPilot GCS + OpenPilot GCS Home + OpenPilot Object Browser Settings Connect Disconnect - OpenPilot Object Browser + Settings + Automatically Connect + Connection Type + Bluetooth + Select the connection method diff --git a/androidgcs/res/xml/preferences.xml b/androidgcs/res/xml/preferences.xml new file mode 100644 index 000000000..d731f59dd --- /dev/null +++ b/androidgcs/res/xml/preferences.xml @@ -0,0 +1,12 @@ + + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/HomePage.java b/androidgcs/src/org/openpilot/androidgcs/HomePage.java new file mode 100644 index 000000000..478c7cdca --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/HomePage.java @@ -0,0 +1,23 @@ +package org.openpilot.androidgcs; + +import android.content.Intent; +import android.os.Bundle; +import android.view.View; +import android.view.View.OnClickListener; +import android.widget.Button; + +public class HomePage extends ObjectManagerActivity { + /** Called when the activity is first created. */ + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.gcs_home); + Button objectBrowser = (Button) findViewById(R.id.launch_object_browser); + objectBrowser.setOnClickListener(new OnClickListener() { + public void onClick(View arg0) { + startActivity(new Intent(HomePage.this, ObjectBrowser.class)); + } + }); + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 7b3030d4f..5af7c7d60 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -16,6 +16,7 @@ import android.app.PendingIntent; import android.app.Service; import android.content.Context; import android.content.Intent; +import android.content.SharedPreferences; import android.net.Uri; import android.os.Binder; import android.os.Handler; @@ -24,6 +25,7 @@ import android.os.IBinder; import android.os.Looper; import android.os.Message; import android.os.Process; +import android.preference.PreferenceManager; import android.util.Log; import android.widget.Toast; @@ -48,8 +50,7 @@ public class OPTelemetryService extends Service { // Message ids static final int MSG_START = 0; - static final int MSG_CONNECT_BT = 1; - static final int MSG_CONNECT_FAKE = 2; + static final int MSG_CONNECT = 1; static final int MSG_DISCONNECT = 3; static final int MSG_TOAST = 100; @@ -70,14 +71,22 @@ public class OPTelemetryService extends Service { Toast.makeText(OPTelemetryService.this, "HERE", Toast.LENGTH_SHORT); System.out.println("HERE"); stopSelf(msg.arg2); - case MSG_CONNECT_BT: + case MSG_CONNECT: terminate = false; - activeTelem = new BTTelemetryThread(); - activeTelem.start(); - break; - case MSG_CONNECT_FAKE: - terminate = false; - activeTelem = new FakeTelemetryThread(); + SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); + int connection_type = Integer.decode(prefs.getString("connection_type", "")); + switch(connection_type) { + case 0: // No connection + return; + case 1: + activeTelem = new FakeTelemetryThread(); + break; + case 2: + activeTelem = new BTTelemetryThread(); + break; + case 3: + throw new Error("Unsupported"); + } activeTelem.start(); break; case MSG_DISCONNECT: @@ -146,14 +155,9 @@ public class OPTelemetryService extends Service { public TelemTask getTelemTask(int id) { return (TelemTask) activeTelem; } - public void openFakeConnection() { + public void openConnection() { Message msg = mServiceHandler.obtainMessage(); - msg.arg1 = MSG_CONNECT_FAKE; - mServiceHandler.sendMessage(msg); - } - public void openBTConnection() { - Message msg = mServiceHandler.obtainMessage(); - msg.arg1 = MSG_CONNECT_BT; + msg.arg1 = MSG_CONNECT; mServiceHandler.sendMessage(msg); } public void stopConnection() { @@ -161,6 +165,9 @@ public class OPTelemetryService extends Service { msg.arg1 = MSG_DISCONNECT; mServiceHandler.sendMessage(msg); } + public boolean isConnected() { + return activeTelem != null; + } }; public void toastMessage(String msgText) { diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index f68e839c1..f3cc56d47 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -6,15 +6,20 @@ import java.util.ListIterator; import java.util.Observable; import java.util.Observer; +import android.content.Intent; +import android.content.SharedPreferences; +import android.content.SharedPreferences.OnSharedPreferenceChangeListener; import android.database.DataSetObserver; import android.os.Bundle; import android.os.Handler; +import android.preference.PreferenceManager; import android.util.Log; import android.view.Menu; import android.view.MenuInflater; import android.view.MenuItem; import android.view.View; import android.view.ViewGroup; +import android.widget.Adapter; import android.widget.ArrayAdapter; import android.widget.ExpandableListAdapter; import android.widget.ExpandableListView; @@ -27,36 +32,13 @@ import android.widget.Toast; import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObject; -public class ObjectBrowser extends ObjectManagerActivity { - - @Override - public boolean onOptionsItemSelected(MenuItem item) { - switch(item.getItemId()) { - case R.id.menu_connect: - binder.openBTConnection(); - return true; - case R.id.menu_disconnect: - binder.stopConnection(); - updateText.run(); - return true; - case R.id.menu_settings: - return true; - default: - return super.onOptionsItemSelected(item); - } - - } - - @Override - public boolean onCreateOptionsMenu(Menu menu) { - MenuInflater inflater = getMenuInflater(); - inflater.inflate(R.menu.options_menu, menu); - return true; - } +public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPreferenceChangeListener { private final String TAG = "ObjectBrower"; boolean connected; - + SharedPreferences prefs; + ArrayAdapter adapter; + final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { public void run() { @@ -70,6 +52,8 @@ public class ObjectBrowser extends ObjectManagerActivity { public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); setContentView(R.layout.main); + prefs = PreferenceManager.getDefaultSharedPreferences(this); + prefs.registerOnSharedPreferenceChangeListener(this); } @Override @@ -77,6 +61,17 @@ public class ObjectBrowser extends ObjectManagerActivity { Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); Log.d(TAG, "onOPConnected()"); + List> allobjects = objMngr.getDataObjects(); + List linearized = new ArrayList(); + ListIterator> li = allobjects.listIterator(); + while(li.hasNext()) { + linearized.addAll(li.next()); + } + + adapter = new ArrayAdapter(this,R.layout.object_view, linearized); + ListView objects = (ListView) findViewById(R.id.object_list); + objects.setAdapter(adapter); + UAVObject obj = objMngr.getObject("SystemStats"); if(obj != null) obj.addUpdatedObserver(new Observer() { @@ -88,16 +83,12 @@ public class ObjectBrowser extends ObjectManagerActivity { } public void update() { - List> allobjects = objMngr.getDataObjects(); - List linearized = new ArrayList(); - ListIterator> li = allobjects.listIterator(); - while(li.hasNext()) { - linearized.addAll(li.next()); - } - - ArrayAdapter adapter = new ArrayAdapter(this,R.layout.object_view, linearized); - ListView objects = (ListView) findViewById(R.id.object_list); - objects.setAdapter(adapter); + adapter.notifyDataSetChanged(); + } + public void onSharedPreferenceChanged(SharedPreferences sharedPreferences, + String key) { + // TODO Auto-generated method stub + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java index 12a072de7..d91946b92 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -14,6 +14,9 @@ import android.content.ServiceConnection; import android.os.Bundle; import android.os.IBinder; import android.util.Log; +import android.view.Menu; +import android.view.MenuInflater; +import android.view.MenuItem; public abstract class ObjectManagerActivity extends Activity { @@ -72,6 +75,31 @@ public abstract class ObjectManagerActivity extends Activity { } + @Override + public boolean onOptionsItemSelected(MenuItem item) { + switch(item.getItemId()) { + case R.id.menu_connect: + binder.openConnection(); + return true; + case R.id.menu_disconnect: + binder.stopConnection(); + return true; + case R.id.menu_settings: + startActivity(new Intent(this, Preferences.class)); + return true; + default: + return super.onOptionsItemSelected(item); + } + + } + + @Override + public boolean onCreateOptionsMenu(Menu menu) { + MenuInflater inflater = getMenuInflater(); + inflater.inflate(R.menu.options_menu, menu); + return true; + } + @Override public void onStart() { super.onStart(); diff --git a/androidgcs/src/org/openpilot/androidgcs/Preferences.java b/androidgcs/src/org/openpilot/androidgcs/Preferences.java new file mode 100644 index 000000000..913de0f73 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/Preferences.java @@ -0,0 +1,12 @@ +package org.openpilot.androidgcs; + +import android.os.Bundle; +import android.preference.PreferenceActivity; + +public class Preferences extends PreferenceActivity { + @Override + protected void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + addPreferencesFromResource(R.xml.preferences); + } +} From fd3a02eb92ddd89d6b1faefe8c2382f1570167a1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 21 Mar 2011 18:33:47 -0500 Subject: [PATCH 234/543] More work on the object browser/editor. Hard to make it resize itself though. --- androidgcs/AndroidManifest.xml | 1 + androidgcs/Doc/.AndroidArchitecture.txt.swp | Bin 12288 -> 0 bytes .../layout/{main.xml => object_browser.xml} | 0 androidgcs/res/layout/object_edit.xml | 9 +++ .../openpilot/androidgcs/ObjectBrowser.java | 44 ++++++++------- .../openpilot/androidgcs/ObjectEditor.java | 52 ++++++++++++++++++ .../androidgcs/ObjectManagerActivity.java | 23 +++++++- 7 files changed, 108 insertions(+), 21 deletions(-) delete mode 100644 androidgcs/Doc/.AndroidArchitecture.txt.swp rename androidgcs/res/layout/{main.xml => object_browser.xml} (100%) create mode 100644 androidgcs/res/layout/object_edit.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index a791d0fbb..fe8c6ae9a 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -26,6 +26,7 @@ + diff --git a/androidgcs/Doc/.AndroidArchitecture.txt.swp b/androidgcs/Doc/.AndroidArchitecture.txt.swp deleted file mode 100644 index 167a072526a8207b396d71d6dd7d3e7a417cba19..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 12288 zcmeHNzmFS56rMwnA3z`iK>^J`id>>QJ0S%T4RS8dVU#03?7Kh}jd#cP-0jXRGqdLy zB_JeP;2%IhK?4;OL^LQ=G-;^`1>rxSqu_h9yY}UZv?yp!`Qr2bn0fDe-}~N1+2N_J z-UffYb%x>RC}UrI^6`eazqIt*H;ip3#(SgBo~CmT`FUIA`E0F~nM7m{xr}`{U$A}N zBxNqOckRp8jIGFXrN`|{h18c-W_(-d)EbqJ6GxY}JJr{YO(x3A#FtjK{0;xG&EmPp zKxAOSK2dF}KmI(Y2WSNQYKZ7$Bo-y#E%fyh8)ATkgchzvvqA_I|u|2+e~ zSYjU`%g5?WFVvq)`#$Th@gp)28Hfx-1|kEIfyh8)ATkgchzvvqA_I|uN00%LGPe3S zW8w(}kN^K~{{8>wvy6QWdgNH7@GiVz&YUWBaGb!egqV740sWE0XPKw z{4`@0=mO_~lfb>F82cRP0!M*ofjdt!whJr+$AP~NGj<=i3)}=&fZq=>_6u+am;%ed z%fL&(-Ghw%0DKSJ0&W6r;2>}SxP5@J?|^TC1b7#?2Al(q0{?)6KY)9{ufSKpm%uIH zCJ;D!1Zx~ajtoQw{v!rDLzO8%3N*zup~i9E8`N zJjt(=($1ROmC@XJ;Y%0Jt%)q-ixtDMb+s$`1g~IalEU^A$uAAJvEPQ!Vk~WlMhc{| z+1bJ!d>}KKOOH)@=af#RWz3aDVXT*Fi}iSFw8t_^?}Wu_0x0t`OR*ESqfJcV5uM{= zXiCqg6IJbi16DEy2JlW;QP7eDT)l4K9sH7M5==$7f5Rz69N4eGEt)$7oa0aK>dR<<+V;*EZhkKkq=f0;#uJWRh7h|Lk)@Mia*XtyY#&& zZ&P+!eJnl81(K?`_p@bp0t|FA4-tfozxuZv%GMYV5G@j`J6 zy5|AVh8{o$Lu5PWw$TtDS(68fK+`@G=y$Jf_13zT3-nFZvp2l7T4daWb|zs;NP;A2 z<(RC7`h?s^4AJ|}YlBe!Esc)S*+4( zVXz0Jx=DhbcZh^O(6Wiip%Xq8!7NiU9#D!uWPYRr+*Jk6mt6^O5H9GbdN-7=fY?G2 zKqZt<w>-1wnI&T9)>r`IggCxCM`qiRMFH(r;p=PLhmUW2tq;~>J3K{ zE@~y3gMwQW(#?=$4srAA~;j1tIlNGZG^8G*3NuIRz$>-_K0|9#2o7)E zy0$aPj`Sd1^D6_g-Fh==!;D$w8{K}tv)<*GJN z%~W%*a@k^KkwQ03=yfqrhy(^WMiQ{XP&Dw5tf{9ObFD)iG$zf~s?3mXt&3{yFhFYt zLUMI{W)!}SFonYu2;1PDnASejO27?lH&?XqC1*CKB2< zJRd2H4ssgICx|G+fTt48MX*tgmL`RI(p33h$kce^=a=@Oe8i7VUSI1!c$Bh$@MKO} z)yAt)QxAH8;9x{Ma{lmmg0?`p(M<5NMIcQCRwfb;P%hM!HY3^6{aAa>5fmB5hHtb? zVZnXGHoT4&hb!U1?v2pE^H6zZEvPGvF2pr&X_;cKVK49(?j|=txdk7|DGdht+4F>0 I9l+o0U$ht(TmS$7 diff --git a/androidgcs/res/layout/main.xml b/androidgcs/res/layout/object_browser.xml similarity index 100% rename from androidgcs/res/layout/main.xml rename to androidgcs/res/layout/object_browser.xml diff --git a/androidgcs/res/layout/object_edit.xml b/androidgcs/res/layout/object_edit.xml new file mode 100644 index 000000000..62a482be9 --- /dev/null +++ b/androidgcs/res/layout/object_edit.xml @@ -0,0 +1,9 @@ + + + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index f3cc56d47..df2d114a4 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -9,25 +9,16 @@ import java.util.Observer; import android.content.Intent; import android.content.SharedPreferences; import android.content.SharedPreferences.OnSharedPreferenceChangeListener; -import android.database.DataSetObserver; import android.os.Bundle; import android.os.Handler; import android.preference.PreferenceManager; import android.util.Log; -import android.view.Menu; -import android.view.MenuInflater; -import android.view.MenuItem; import android.view.View; -import android.view.ViewGroup; -import android.widget.Adapter; +import android.widget.AdapterView; import android.widget.ArrayAdapter; -import android.widget.ExpandableListAdapter; -import android.widget.ExpandableListView; import android.widget.ListView; -import android.widget.SimpleAdapter; -import android.widget.SimpleExpandableListAdapter; -import android.widget.TextView; import android.widget.Toast; +import android.widget.AdapterView.OnItemClickListener; import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObject; @@ -38,6 +29,7 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref boolean connected; SharedPreferences prefs; ArrayAdapter adapter; + List allObjects; final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { @@ -51,7 +43,7 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref @Override public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); - setContentView(R.layout.main); + setContentView(R.layout.object_browser); prefs = PreferenceManager.getDefaultSharedPreferences(this); prefs.registerOnSharedPreferenceChangeListener(this); } @@ -60,18 +52,32 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref void onOPConnected() { Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); Log.d(TAG, "onOPConnected()"); - + List> allobjects = objMngr.getDataObjects(); - List linearized = new ArrayList(); + allObjects = new ArrayList(); ListIterator> li = allobjects.listIterator(); while(li.hasNext()) { - linearized.addAll(li.next()); + allObjects.addAll(li.next()); } - - adapter = new ArrayAdapter(this,R.layout.object_view, linearized); + + adapter = new ArrayAdapter(this,R.layout.object_view, allObjects); ListView objects = (ListView) findViewById(R.id.object_list); objects.setAdapter(adapter); + objects.setOnItemClickListener(new OnItemClickListener() { + public void onItemClick(AdapterView parent, View view, + int position, long id) { + /*Toast.makeText(getApplicationContext(), ((TextView) view).getText(), + Toast.LENGTH_SHORT).show();*/ + Intent intent = new Intent(ObjectBrowser.this, ObjectEditor.class); + intent.putExtra("org.openpilot.androidgcs.ObjectName", allObjects.get(position).getName()); + intent.putExtra("org.openpilot.androidgcs.ObjectId", allObjects.get(position).getObjID()); + intent.putExtra("org.openpilot.androidgcs.InstId", allObjects.get(position).getInstID()); + startActivity(intent); + } + }); + + UAVObject obj = objMngr.getObject("SystemStats"); if(obj != null) obj.addUpdatedObserver(new Observer() { @@ -81,7 +87,7 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref }); } - + public void update() { adapter.notifyDataSetChanged(); } @@ -89,6 +95,6 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref public void onSharedPreferenceChanged(SharedPreferences sharedPreferences, String key) { // TODO Auto-generated method stub - + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java b/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java new file mode 100644 index 000000000..33d0e2f8e --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java @@ -0,0 +1,52 @@ +package org.openpilot.androidgcs; + +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVObjectField; + +import android.os.Bundle; +import android.widget.LinearLayout; +import android.widget.TextView; +import android.widget.Toast; + +public class ObjectEditor extends ObjectManagerActivity { + + String objectName; + int objectID; + int instID; + + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.object_edit); + + System.out.println("Started. Intent:" + getIntent()); + Bundle extras = getIntent().getExtras(); + if(extras != null){ + objectName = extras.getString("org.openpilot.androidgcs.ObjectName"); + objectID = extras.getInt("org.openpilot.androidgcs.ObjectId"); + instID = extras.getInt("org.openpilot.androidgcs.InstId"); + } + } + + public void onOPConnected() { + UAVObject obj = objMngr.getObject(objectID, instID); + Toast.makeText(getApplicationContext(), obj.toString(), Toast.LENGTH_SHORT); + + TextView objectName = (TextView) findViewById(R.id.object_edit_name); + objectName.setText(obj.getName()); + + LinearLayout fieldViewList = (LinearLayout) findViewById(R.id.object_edit_fields); + List fields = obj.getFields(); + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + UAVObjectField field = li.next(); + TextView fieldName = new TextView(this); + fieldName.setText(field.getName()); + fieldViewList.addView(fieldName); + } + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java index d91946b92..5027d4d24 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -21,7 +21,7 @@ import android.view.MenuItem; public abstract class ObjectManagerActivity extends Activity { private final String TAG = "ObjectManagerActivity"; - private static int LOGLEVEL = 2; + private static int LOGLEVEL = 0; // private static boolean WARN = LOGLEVEL > 1; private static boolean DEBUG = LOGLEVEL > 0; @@ -106,19 +106,38 @@ public abstract class ObjectManagerActivity extends Activity { Intent intent = new Intent(this, OPTelemetryService.class); bindService(intent, mConnection, Context.BIND_AUTO_CREATE); } + + public void onBind() { + + } /** Defines callbacks for service binding, passed to bindService() */ private ServiceConnection mConnection = new ServiceConnection() { public void onServiceConnected(ComponentName arg0, IBinder service) { // We've bound to LocalService, cast the IBinder and attempt to open a connection if (DEBUG) Log.d(TAG,"Service bound"); - binder = (LocalBinder) service; + mBound = true; + binder = (LocalBinder) service; + + if(binder.isConnected()) { + TelemTask task; + if((task = binder.getTelemTask(0)) != null) { + objMngr = task.getObjectManager(); + mConnected = true; + onOPConnected(); + } + + } } public void onServiceDisconnected(ComponentName name) { mBound = false; + binder = null; mConnected = false; objMngr = null; + objMngr = null; + mConnected = false; + onOPDisconnected(); } }; } From bee57409835e2faea5b4f28bb8e3ef4d0a612ff8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 12:59:01 -0500 Subject: [PATCH 235/543] Added a simple PFD --- androidgcs/AndroidManifest.xml | 9 +- androidgcs/res/drawable-hdpi/browser_icon.png | Bin 0 -> 456 bytes androidgcs/res/drawable-ldpi/browser_icon.png | Bin 0 -> 456 bytes androidgcs/res/drawable-mdpi/browser_icon.png | Bin 0 -> 456 bytes androidgcs/res/layout/gcs_home.xml | 9 +- androidgcs/res/layout/pfd.xml | 8 + androidgcs/res/values/colors.xml | 6 + androidgcs/res/values/strings.xml | 6 + .../openpilot/androidgcs/AttitudeView.java | 89 +++++++++++ .../org/openpilot/androidgcs/CompassView.java | 139 ++++++++++++++++++ .../org/openpilot/androidgcs/HomePage.java | 9 ++ .../src/org/openpilot/androidgcs/PFD.java | 51 +++++++ 12 files changed, 318 insertions(+), 8 deletions(-) create mode 100644 androidgcs/res/drawable-hdpi/browser_icon.png create mode 100644 androidgcs/res/drawable-ldpi/browser_icon.png create mode 100644 androidgcs/res/drawable-mdpi/browser_icon.png create mode 100644 androidgcs/res/layout/pfd.xml create mode 100644 androidgcs/res/values/colors.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/AttitudeView.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/CompassView.java create mode 100644 androidgcs/src/org/openpilot/androidgcs/PFD.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index fe8c6ae9a..1942146c4 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -18,13 +18,8 @@ - - - - - - - + + diff --git a/androidgcs/res/drawable-hdpi/browser_icon.png b/androidgcs/res/drawable-hdpi/browser_icon.png new file mode 100644 index 0000000000000000000000000000000000000000..3fcee485245922172e66bad2eb2203db14cdac39 GIT binary patch literal 456 zcmV;(0XP1MP)2!duSV%belNQ;||iLJSe+;1>Z9S#NM0kJ-$^wmm*RY+To8 zv9OU+Vp%S#Dwxlg2qCa-7b$%#%SVV+t!?|?eYIMiWKtswJ$f(3w;l5V%m%S&OW63?^9=i}S!{|oRH^?GKj631~Um0~;V0=*5_l}PE6%PFYp yZavDW{)W@(8>Xp~%_jEdoebdExV#6+x#JU=$8dKofqu*Y00002!duSV%belNQ;||iLJSe+;1>Z9S#NM0kJ-$^wmm*RY+To8 zv9OU+Vp%S#Dwxlg2qCa-7b$%#%SVV+t!?|?eYIMiWKtswJ$f(3w;l5V%m%S&OW63?^9=i}S!{|oRH^?GKj631~Um0~;V0=*5_l}PE6%PFYp yZavDW{)W@(8>Xp~%_jEdoebdExV#6+x#JU=$8dKofqu*Y00002!duSV%belNQ;||iLJSe+;1>Z9S#NM0kJ-$^wmm*RY+To8 zv9OU+Vp%S#Dwxlg2qCa-7b$%#%SVV+t!?|?eYIMiWKtswJ$f(3w;l5V%m%S&OW63?^9=i}S!{|oRH^?GKj631~Um0~;V0=*5_l}PE6%PFYp yZavDW{)W@(8>Xp~%_jEdoebdExV#6+x#JU=$8dKofqu*Y0000 - + diff --git a/androidgcs/res/layout/pfd.xml b/androidgcs/res/layout/pfd.xml new file mode 100644 index 000000000..191a80eb9 --- /dev/null +++ b/androidgcs/res/layout/pfd.xml @@ -0,0 +1,8 @@ + + + + + diff --git a/androidgcs/res/values/colors.xml b/androidgcs/res/values/colors.xml new file mode 100644 index 000000000..dc8eaf315 --- /dev/null +++ b/androidgcs/res/values/colors.xml @@ -0,0 +1,6 @@ + + + #F555 + #AFFF + #AFFF + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index e9b66a312..3b3a38d02 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -2,6 +2,7 @@ OpenPilot GCS Home OpenPilot Object Browser + OpenPilot PFD Settings Connect Disconnect @@ -10,4 +11,9 @@ Connection Type Bluetooth Select the connection method + Compass + N + E + S + W diff --git a/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java b/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java new file mode 100644 index 000000000..24a8bf5f0 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java @@ -0,0 +1,89 @@ +package org.openpilot.androidgcs; + +import android.content.Context; +import android.content.res.Resources; +import android.graphics.Canvas; +import android.graphics.Paint; +import android.util.AttributeSet; +import android.view.View; + +public class AttitudeView extends View { + + public AttitudeView(Context context) { + super(context); + initAttitudeView(); + } + + public AttitudeView(Context context, AttributeSet ats, int defaultStyle) { + super(context, ats, defaultStyle); + initAttitudeView(); + } + + public AttitudeView(Context context, AttributeSet ats) { + super(context, ats); + initAttitudeView(); + } + + protected void initAttitudeView() { + setFocusable(true); + + circlePaint = new Paint(Paint.ANTI_ALIAS_FLAG); + circlePaint.setColor(R.color.background_color); + circlePaint.setStrokeWidth(1); + circlePaint.setStyle(Paint.Style.FILL_AND_STROKE); + Resources r = this.getResources(); + textPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + textPaint.setColor(r.getColor(R.color.text_color)); + markerPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + markerPaint.setColor(r.getColor(R.color.marker_color)); + } + + @Override protected void onMeasure(int widthMeasureSpec, int heightMeasureSpec) { + int measuredWidth = measure(widthMeasureSpec); + int measuredHeight = measure(heightMeasureSpec); + int d = Math.min(measuredWidth, measuredHeight); + setMeasuredDimension(d/2, d/2); + } + + private int measure(int measureSpec) { + int result = 0; + // Decode the measurement specifications. + + int specMode = MeasureSpec.getMode(measureSpec); + int specSize = MeasureSpec.getSize(measureSpec); + + if (specMode == MeasureSpec.UNSPECIFIED) { // Return a default size of 200 if no bounds are specified. + result = 200; + } else { + // As you want to fill the available space + // always return the full available bounds. + result = specSize; + } + return result; + } + + private double roll; + public void setRoll(double roll) { + this.roll = roll; + } + private double pitch; + public void setPitch(double d) { + this.pitch = d; + } + + // Drawing related code + private Paint markerPaint; + private Paint textPaint; + private Paint circlePaint; + + @Override + protected void onDraw(Canvas canvas) { + int px = getMeasuredWidth() / 2; + int py = getMeasuredHeight() /2 ; + int radius = Math.min(px, py); + + canvas.drawLine(px,py, (int) (px+radius * Math.cos(roll)), (int) (py + radius * Math.sin(roll)), markerPaint); + canvas.drawLine(px,py, (int) (px+radius * Math.cos(pitch)), (int) (py + radius * Math.sin(pitch)), markerPaint); + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/CompassView.java b/androidgcs/src/org/openpilot/androidgcs/CompassView.java new file mode 100644 index 000000000..50e4abc0a --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/CompassView.java @@ -0,0 +1,139 @@ +package org.openpilot.androidgcs; + +import android.content.Context; +import android.content.res.Resources; +import android.graphics.Canvas; +import android.graphics.Paint; +import android.util.AttributeSet; +import android.view.View; + +public class CompassView extends View { + + public CompassView(Context context) { + super(context); + initCompassView(); + } + + public CompassView(Context context, AttributeSet ats, int defaultStyle) { + super(context, ats, defaultStyle); + initCompassView(); + } + + public CompassView(Context context, AttributeSet ats) { + super(context, ats); + initCompassView(); + } + + protected void initCompassView() { + setFocusable(true); + + circlePaint = new Paint(Paint.ANTI_ALIAS_FLAG); + circlePaint.setColor(R.color.background_color); + circlePaint.setStrokeWidth(1); + circlePaint.setStyle(Paint.Style.FILL_AND_STROKE); + Resources r = this.getResources(); + northString = r.getString(R.string.cardinal_north); + eastString = r.getString(R.string.cardinal_east); + southString = r.getString(R.string.cardinal_south); + westString = r.getString(R.string.cardinal_west); + textPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + textPaint.setColor(r.getColor(R.color.text_color)); + textHeight = (int)textPaint.measureText("yY"); + markerPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + markerPaint.setColor(r.getColor(R.color.marker_color)); + } + + @Override protected void onMeasure(int widthMeasureSpec, int heightMeasureSpec) { + int measuredWidth = measure(widthMeasureSpec); + int measuredHeight = measure(heightMeasureSpec); + int d = Math.min(measuredWidth, measuredHeight); + setMeasuredDimension(d/2, d/2); + } + + private int measure(int measureSpec) { + int result = 0; + // Decode the measurement specifications. + + int specMode = MeasureSpec.getMode(measureSpec); + int specSize = MeasureSpec.getSize(measureSpec); + + if (specMode == MeasureSpec.UNSPECIFIED) { // Return a default size of 200 if no bounds are specified. + result = 200; + } else { + // As you want to fill the available space + // always return the full available bounds. + result = specSize; + } + return result; + } + + private double bearing; + public void setBearing(double bearing) { + this.bearing = bearing; + } + + // Drawing related code + private Paint markerPaint; + private Paint textPaint; + private Paint circlePaint; + private String northString; + private String eastString; + private String southString; + private String westString; + private int textHeight; + + @Override + protected void onDraw(Canvas canvas) { + int px = getMeasuredWidth() / 2; + int py = getMeasuredHeight() /2 ; + int radius = Math.min(px, py); + // Draw the background + canvas.drawCircle(px, py, radius, circlePaint); + + // Rotate our perspective so that the ÔtopÕ is + // facing the current bearing. + canvas.save(); + canvas.rotate((float) -bearing, px, py); + + int textWidth = (int)textPaint.measureText("W"); + int cardinalX = px-textWidth/2; + int cardinalY = py-radius+textHeight; + + // Draw the marker every 15 degrees and text every 45. + for (int i = 0; i < 24; i++) { + // Draw a marker. + canvas.drawLine(px, py-radius, px, py-radius+10, markerPaint); + canvas.save(); + canvas.translate(0, textHeight); + // Draw the cardinal points + if (i % 6 == 0) { + String dirString = null; + switch (i) { + case 0 : { + dirString = northString; + int arrowY = 2*textHeight; + canvas.drawLine(px, arrowY, px-5, 3*textHeight, markerPaint); + canvas.drawLine(px, arrowY, px+5, 3*textHeight, markerPaint); + break; + } + case 6: dirString = eastString; break; + case 12: dirString = southString; break; + case 18: dirString = westString; break; + } + canvas.drawText(dirString, cardinalX, cardinalY, textPaint); + } + else if (i % 3 == 0) { + // Draw the text every alternate 45deg + String angle = String.valueOf(i*15); + float angleTextWidth = textPaint.measureText(angle); + + int angleTextX = (int)(px-angleTextWidth/2); + int angleTextY = py-radius+textHeight; + canvas.drawText(angle, angleTextX, angleTextY, textPaint); + } + canvas.restore(); + canvas.rotate(15, px, py); + } + canvas.restore(); + } +} diff --git a/androidgcs/src/org/openpilot/androidgcs/HomePage.java b/androidgcs/src/org/openpilot/androidgcs/HomePage.java index 478c7cdca..7d03e1b04 100644 --- a/androidgcs/src/org/openpilot/androidgcs/HomePage.java +++ b/androidgcs/src/org/openpilot/androidgcs/HomePage.java @@ -12,12 +12,21 @@ public class HomePage extends ObjectManagerActivity { public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); setContentView(R.layout.gcs_home); + Button objectBrowser = (Button) findViewById(R.id.launch_object_browser); objectBrowser.setOnClickListener(new OnClickListener() { public void onClick(View arg0) { startActivity(new Intent(HomePage.this, ObjectBrowser.class)); } }); + + Button pfd = (Button) findViewById(R.id.launch_pfd); + pfd.setOnClickListener(new OnClickListener() { + public void onClick(View arg0) { + startActivity(new Intent(HomePage.this, PFD.class)); + } + }); + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/PFD.java b/androidgcs/src/org/openpilot/androidgcs/PFD.java new file mode 100644 index 000000000..e0d1b9f24 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/PFD.java @@ -0,0 +1,51 @@ +package org.openpilot.androidgcs; + +import java.util.Observable; +import java.util.Observer; + +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObject; + +import android.os.Bundle; + +public class PFD extends ObjectManagerActivity { + + double heading; + double roll; + double pitch; + + Runnable update = new Runnable() { + public void run() { + CompassView compass = (CompassView) findViewById(R.id.compass_view); + compass.setBearing((int) heading); + compass.invalidate(); + + AttitudeView attitude = (AttitudeView) findViewById(R.id.attitude_view); + attitude.setRoll(roll / 180 * Math.PI); + attitude.setPitch(pitch / 180 * Math.PI); + attitude.invalidate(); + } + }; + + @Override + public void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.pfd); + } + + @Override + void onOPConnected() { + + UAVObject obj = objMngr.getObject("AttitudeActual"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + UAVDataObject obj = (UAVDataObject) data; + heading = obj.getField("Yaw").getDouble(); + pitch = obj.getField("Pitch").getDouble(); + roll = obj.getField("Roll").getDouble(); + runOnUiThread(update); + } + }); + } +} From 0950d0386b4dcde192eaef54e8a69f2e43488ff4 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 12:59:17 -0500 Subject: [PATCH 236/543] Make fake telemetry show rotating attitude. --- .../org/openpilot/androidgcs/OPTelemetryService.java | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 5af7c7d60..43cc13b04 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -200,8 +200,19 @@ public class OPTelemetryService extends Service { //toastMessage("Started fake telemetry thread"); UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); + UAVDataObject attitudeActual = (UAVDataObject) objMngr.getObject("AttitudeActual"); + double roll = 0; + double pitch = 0; + double yaw = 0; while( !terminate ) { + attitudeActual.getField("Roll").setDouble(roll); + attitudeActual.getField("Pitch").setDouble(pitch); + attitudeActual.getField("Yaw").setDouble(yaw); + roll = (roll + 10) % 180; + pitch = (pitch + 10) % 180; + yaw = (yaw + 10) % 360; systemStats.updated(); + attitudeActual.updated(); try { Thread.sleep(1000); } catch (InterruptedException e) { From c8c7323ab7902377f576a14635cb06b73ad17829 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 13:14:11 -0500 Subject: [PATCH 237/543] Make auto starting work. For now removed support for standalone service but easy to add back. --- .../androidgcs/OPTelemetryService.java | 43 ++++++++++++------- 1 file changed, 27 insertions(+), 16 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 43cc13b04..67ee56d4e 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -68,10 +68,10 @@ public class OPTelemetryService extends Service { public void handleMessage(Message msg) { switch(msg.arg1) { case MSG_START: - Toast.makeText(OPTelemetryService.this, "HERE", Toast.LENGTH_SHORT); - System.out.println("HERE"); stopSelf(msg.arg2); - case MSG_CONNECT: + break; + case MSG_CONNECT: + Toast.makeText(getApplicationContext(), "Attempting connection", Toast.LENGTH_SHORT).show(); terminate = false; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); int connection_type = Integer.decode(prefs.getString("connection_type", "")); @@ -90,6 +90,7 @@ public class OPTelemetryService extends Service { activeTelem.start(); break; case MSG_DISCONNECT: + Toast.makeText(getApplicationContext(), "Disconnct", Toast.LENGTH_SHORT).show(); terminate = true; try { activeTelem.join(); @@ -101,6 +102,8 @@ public class OPTelemetryService extends Service { Intent intent = new Intent(); intent.setAction(INTENT_ACTION_DISCONNECTED); sendBroadcast(intent,null); + + stopSelf(); break; case MSG_TOAST: @@ -113,9 +116,9 @@ public class OPTelemetryService extends Service { } }; - @Override - public void onCreate() { - // Low priority thread for message handling with service + public void startup() { + Toast.makeText(getApplicationContext(), "Telemetry service starting", Toast.LENGTH_SHORT).show(); + HandlerThread thread = new HandlerThread("TelemetryServiceHandler", Process.THREAD_PRIORITY_BACKGROUND); thread.start(); @@ -123,20 +126,27 @@ public class OPTelemetryService extends Service { // Get the HandlerThread's Looper and use it for our Handler mServiceLooper = thread.getLooper(); mServiceHandler = new ServiceHandler(mServiceLooper); + + SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); + if(prefs.getBoolean("autoconnect", false)) { + Toast.makeText(getApplicationContext(), "Should auto connect", Toast.LENGTH_SHORT); + Message msg = mServiceHandler.obtainMessage(); + msg.arg1 = MSG_CONNECT; + msg.arg2 = 0; + mServiceHandler.sendMessage(msg); + } + + } + + @Override + public void onCreate() { + startup(); } @Override public int onStartCommand(Intent intent, int flags, int startId) { - Toast.makeText(this, "Telemetry service starting", Toast.LENGTH_SHORT).show(); - - System.out.println("Start"); - // For each start request, send a message to start a job and deliver the - // start ID so we know which request we're stopping when we finish the job - Message msg = mServiceHandler.obtainMessage(); - msg.arg1 = MSG_START; - msg.arg2 = startId; - mServiceHandler.sendMessage(msg); - + // Currently only using as bound service + // If we get killed, after returning from here, restart return START_STICKY; } @@ -156,6 +166,7 @@ public class OPTelemetryService extends Service { return (TelemTask) activeTelem; } public void openConnection() { + Toast.makeText(getApplicationContext(), "Requested open connection", Toast.LENGTH_SHORT); Message msg = mServiceHandler.obtainMessage(); msg.arg1 = MSG_CONNECT; mServiceHandler.sendMessage(msg); From 2139954e49d83beadc4d49be95875c6bda5aae95 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 21:39:44 -0500 Subject: [PATCH 238/543] Added location feature and made fake stream create movement --- androidgcs/AndroidManifest.xml | 18 +- androidgcs/default.properties | 2 +- androidgcs/res/layout/gcs_home.xml | 1 + androidgcs/res/layout/map_layout.xml | 10 + androidgcs/res/values/strings.xml | 37 ++- .../org/openpilot/androidgcs/HomePage.java | 6 + .../androidgcs/OPTelemetryService.java | 27 ++ .../org/openpilot/androidgcs/UAVLocation.java | 273 ++++++++++++++++++ 8 files changed, 351 insertions(+), 23 deletions(-) create mode 100644 androidgcs/res/layout/map_layout.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/UAVLocation.java diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 1942146c4..c18dc0cb1 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -4,10 +4,14 @@ android:versionName="1.0"> + + + + @@ -16,13 +20,15 @@ - - + + - - - - + + + + + diff --git a/androidgcs/default.properties b/androidgcs/default.properties index 66db0d159..420db56e3 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=android-10 +target=Google Inc.:Google APIs:8 diff --git a/androidgcs/res/layout/gcs_home.xml b/androidgcs/res/layout/gcs_home.xml index 1a5a81cd7..e07f5b003 100644 --- a/androidgcs/res/layout/gcs_home.xml +++ b/androidgcs/res/layout/gcs_home.xml @@ -11,4 +11,5 @@ android:id="@+id/launch_object_browser" android:drawableLeft="@drawable/browser_icon" android:layout_centerHorizontal="true"/> + diff --git a/androidgcs/res/layout/map_layout.xml b/androidgcs/res/layout/map_layout.xml new file mode 100644 index 000000000..64c64b16e --- /dev/null +++ b/androidgcs/res/layout/map_layout.xml @@ -0,0 +1,10 @@ + + + + + \ No newline at end of file diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 3b3a38d02..7cef563e7 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -1,19 +1,24 @@ - OpenPilot GCS Home - OpenPilot Object Browser - OpenPilot PFD - Settings - Connect - Disconnect - Settings - Automatically Connect - Connection Type - Bluetooth - Select the connection method - Compass - N - E - S - W + OpenPilot GCS Home + OpenPilot Object Browser + OpenPilot PFD + OpenPilot Location + + Settings + Connect + Disconnect + + Settings + Automatically Connect + Connection Type + Bluetooth + Select the connection method + + Compass + N + E + S + W + Connected diff --git a/androidgcs/src/org/openpilot/androidgcs/HomePage.java b/androidgcs/src/org/openpilot/androidgcs/HomePage.java index 7d03e1b04..cf9664d14 100644 --- a/androidgcs/src/org/openpilot/androidgcs/HomePage.java +++ b/androidgcs/src/org/openpilot/androidgcs/HomePage.java @@ -27,6 +27,12 @@ public class HomePage extends ObjectManagerActivity { } }); + Button location = (Button) findViewById(R.id.launch_location); + location.setOnClickListener(new OnClickListener() { + public void onClick(View arg0) { + startActivity(new Intent(HomePage.this, UAVLocation.class)); + } + }); } } diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 67ee56d4e..c2914f34a 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -212,18 +212,45 @@ public class OPTelemetryService extends Service { //toastMessage("Started fake telemetry thread"); UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); UAVDataObject attitudeActual = (UAVDataObject) objMngr.getObject("AttitudeActual"); + UAVDataObject homeLocation = (UAVDataObject) objMngr.getObject("HomeLocation"); + UAVDataObject positionActual = (UAVDataObject) objMngr.getObject("PositionActual"); + + homeLocation.getField("Latitude").setDouble(379420315); + homeLocation.getField("Longitude").setDouble(-88330078); + homeLocation.getField("ECEF").setDouble(497665694,0); + homeLocation.getField("ECEF").setDouble(-77336320,1); + homeLocation.getField("ECEF").setDouble(390037169,2); + homeLocation.getField("RNE").setDouble(-0.60757166,0); + homeLocation.getField("RNE").setDouble(0.09441550,1); + homeLocation.getField("RNE").setDouble(0.78863323,2); + homeLocation.getField("RNE").setDouble(0.15355512,3); + homeLocation.getField("RNE").setDouble(0.98814011,4); + homeLocation.getField("RNE").setDouble(0,5); + homeLocation.getField("RNE").setDouble(-0.77928013,6); + homeLocation.getField("RNE").setDouble(0.12109867,7); + homeLocation.getField("RNE").setDouble(-0.61486387,8); + homeLocation.getField("Be").setDouble(26702.78710938,0); + homeLocation.getField("Be").setDouble(-1468.33605957,1); + homeLocation.getField("Be").setDouble(34181.78515625,2); + + double roll = 0; double pitch = 0; double yaw = 0; + double north = 0; + double east = 0; while( !terminate ) { attitudeActual.getField("Roll").setDouble(roll); attitudeActual.getField("Pitch").setDouble(pitch); attitudeActual.getField("Yaw").setDouble(yaw); + positionActual.getField("North").setDouble(north += 100); + positionActual.getField("East").setDouble(east += 100); roll = (roll + 10) % 180; pitch = (pitch + 10) % 180; yaw = (yaw + 10) % 360; systemStats.updated(); attitudeActual.updated(); + positionActual.updated(); try { Thread.sleep(1000); } catch (InterruptedException e) { diff --git a/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java b/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java new file mode 100644 index 000000000..72085c1d6 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java @@ -0,0 +1,273 @@ +package org.openpilot.androidgcs; + +import java.util.List; +import java.util.Observable; +import java.util.Observer; + +import org.openpilot.androidgcs.OPTelemetryService.LocalBinder; +import org.openpilot.androidgcs.OPTelemetryService.TelemTask; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVObjectManager; + +import com.google.android.maps.GeoPoint; +import com.google.android.maps.MapActivity; +import com.google.android.maps.MapController; +import com.google.android.maps.MapView; +import com.google.android.maps.Overlay; +import com.google.android.maps.Projection; + +import android.content.BroadcastReceiver; +import android.content.ComponentName; +import android.content.Context; +import android.content.Intent; +import android.content.IntentFilter; +import android.content.ServiceConnection; +import android.graphics.Canvas; +import android.graphics.Paint; +import android.graphics.Point; +import android.graphics.RectF; +import android.os.Bundle; +import android.os.IBinder; +import android.util.Log; +import android.view.Menu; +import android.view.MenuInflater; +import android.view.MenuItem; + +public class UAVLocation extends MapActivity +{ + private final String TAG = "UAVLocation"; + private static int LOGLEVEL = 0; +// private static boolean WARN = LOGLEVEL > 1; + private static boolean DEBUG = LOGLEVEL > 0; + + private MapView mapView; + private MapController mapController; + + UAVObjectManager objMngr; + boolean mBound = false; + boolean mConnected = false; + LocalBinder binder; + + GeoPoint homeLocation; + GeoPoint uavLocation; + + @Override public void onCreate(Bundle icicle) { + super.onCreate(icicle); + setContentView(R.layout.map_layout); + mapView = (MapView)findViewById(R.id.map_view); + mapController = mapView.getController(); + + mapView.displayZoomControls(true); + Double lat = 37.422006*1E6; + Double lng = -122.084095*1E6; + homeLocation = new GeoPoint(lat.intValue(), lng.intValue()); + uavLocation = homeLocation; + mapController.setCenter(homeLocation); + mapController.setZoom(18); + + List overlays = mapView.getOverlays(); + UAVOverlay myOverlay = new UAVOverlay(); + overlays.add(myOverlay); + mapView.postInvalidate(); + + // ObjectManager related stuff (can't inherit standard class) + BroadcastReceiver connectedReceiver = new BroadcastReceiver() { + @Override + public void onReceive(Context context, Intent intent) { + Log.d(TAG, "Received intent"); + TelemTask task; + if(intent.getAction().compareTo(OPTelemetryService.INTENT_ACTION_CONNECTED) == 0) { + + if(binder == null) + return; + if((task = binder.getTelemTask(0)) == null) + return; + objMngr = task.getObjectManager(); + mConnected = true; + onOPConnected(); + Log.d(TAG, "Connected()"); + } else if (intent.getAction().compareTo(OPTelemetryService.INTENT_ACTION_DISCONNECTED) == 0) { + objMngr = null; + mConnected = false; + onOPDisconnected(); + Log.d(TAG, "Disonnected()"); + } + } + }; + + IntentFilter filter = new IntentFilter(); + filter.addCategory(OPTelemetryService.INTENT_CATEGORY_GCS); + filter.addAction(OPTelemetryService.INTENT_ACTION_CONNECTED); + filter.addAction(OPTelemetryService.INTENT_ACTION_DISCONNECTED); + registerReceiver(connectedReceiver, filter); + } + + //@Override + protected boolean isRouteDisplayed() { + // IMPORTANT: This method must return true if your Activity // is displaying driving directions. Otherwise return false. + return false; + } + + public class UAVOverlay extends Overlay { + @Override + public void draw(Canvas canvas, MapView mapView, boolean shadow) { + + Projection projection = mapView.getProjection(); + + if (shadow == false) { + Point myPoint = new Point(); + projection.toPixels(uavLocation, myPoint); + + //// Draw UAV + // Create and setup your paint brush + Paint paint = new Paint(); + paint.setARGB(250, 255, 0, 0); + paint.setAntiAlias(true); + paint.setFakeBoldText(true); + + // Create the circle + int rad = 5; + RectF oval = new RectF(myPoint.x-rad, myPoint.y-rad, myPoint.x+rad, myPoint.y+rad); + + // Draw on the canvas + canvas.drawOval(oval, paint); + canvas.drawText("UAV", myPoint.x+rad, myPoint.y, paint); + + //// Draw Home + myPoint = new Point(); + projection.toPixels(homeLocation, myPoint); + + // Create and setup your paint brush + paint.setARGB(250, 0, 0, 0); + paint.setAntiAlias(true); + paint.setFakeBoldText(true); + + // Create the circle + rad = 5; + oval = new RectF(myPoint.x-rad, myPoint.y-rad, myPoint.x+rad, myPoint.y+rad); + + // Draw on the canvas + canvas.drawOval(oval, paint); + canvas.drawText("Home", myPoint.x+rad, myPoint.y, paint); + + } + } + + @Override + public boolean onTap(GeoPoint point, MapView mapView1) { + // Return true if screen tap is handled by this overlay + return false; + } + } + + void onOPConnected() { + UAVObject obj = objMngr.getObject("HomeLocation"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + UAVDataObject obj = (UAVDataObject) data; + Double lat = obj.getField("Latitude").getDouble() / 10; + Double lon = obj.getField("Longitude").getDouble() / 10; + homeLocation = new GeoPoint(lat.intValue(), lon.intValue()); + runOnUiThread(new Runnable() { + public void run() { + mapController.setCenter(homeLocation); + } + }); + System.out.println("HomeLocation: " + homeLocation.toString()); + } + }); + // Hacky - trigger an update + obj.updated(); + + obj = objMngr.getObject("PositionActual"); + if(obj != null) + obj.addUpdatedObserver(new Observer() { + public void update(Observable observable, Object data) { + UAVDataObject obj = (UAVDataObject) data; + Double north = obj.getField("North").getDouble(); + Double east = obj.getField("East").getDouble(); + // TODO: Correct convertion from NED to LLA. This is erroneous conversion from cm to deg + uavLocation = new GeoPoint((int) (homeLocation.getLatitudeE6() + north / 100 * 1e6 / 78847), + (int) (homeLocation.getLongitudeE6() + east / 100 * 1e6 / 78847)); + runOnUiThread(new Runnable() { + public void run() { + mapView.invalidate(); + } + }); + } + }); + + } + + void onOPDisconnected() { + + } + + @Override + public boolean onOptionsItemSelected(MenuItem item) { + switch(item.getItemId()) { + case R.id.menu_connect: + binder.openConnection(); + return true; + case R.id.menu_disconnect: + binder.stopConnection(); + return true; + case R.id.menu_settings: + startActivity(new Intent(this, Preferences.class)); + return true; + default: + return super.onOptionsItemSelected(item); + } + + } + + @Override + public boolean onCreateOptionsMenu(Menu menu) { + MenuInflater inflater = getMenuInflater(); + inflater.inflate(R.menu.options_menu, menu); + return true; + } + + @Override + public void onStart() { + super.onStart(); + Intent intent = new Intent(this, OPTelemetryService.class); + bindService(intent, mConnection, Context.BIND_AUTO_CREATE); + } + + public void onBind() { + + } + + /** Defines callbacks for service binding, passed to bindService() */ + private ServiceConnection mConnection = new ServiceConnection() { + public void onServiceConnected(ComponentName arg0, IBinder service) { + // We've bound to LocalService, cast the IBinder and attempt to open a connection + if (DEBUG) Log.d(TAG,"Service bound"); + mBound = true; + binder = (LocalBinder) service; + + if(binder.isConnected()) { + TelemTask task; + if((task = binder.getTelemTask(0)) != null) { + objMngr = task.getObjectManager(); + mConnected = true; + onOPConnected(); + } + + } + } + + public void onServiceDisconnected(ComponentName name) { + mBound = false; + binder = null; + mConnected = false; + objMngr = null; + objMngr = null; + mConnected = false; + onOPDisconnected(); + } + }; +} From dadcb3939621c19ce14c681486bb0541346a7155 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 22 Mar 2011 21:59:36 -0500 Subject: [PATCH 239/543] Few tweaks and suppress some warnings --- androidgcs/default.properties | 2 +- androidgcs/res/xml/preferences.xml | 23 ++++++++++-------- .../openpilot/androidgcs/TelemetryWidget.java | 24 ++++++++++++++++++- .../uavobjects/UAVObjectsInitialize.java | 2 +- 4 files changed, 38 insertions(+), 13 deletions(-) diff --git a/androidgcs/default.properties b/androidgcs/default.properties index 420db56e3..728f51f97 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=Google Inc.:Google APIs:8 +target=Google Inc.:Google APIs:11 diff --git a/androidgcs/res/xml/preferences.xml b/androidgcs/res/xml/preferences.xml index d731f59dd..24fd43b5e 100644 --- a/androidgcs/res/xml/preferences.xml +++ b/androidgcs/res/xml/preferences.xml @@ -1,12 +1,15 @@ - - - + + + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java index d316526ef..51afdf568 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java +++ b/androidgcs/src/org/openpilot/androidgcs/TelemetryWidget.java @@ -2,11 +2,34 @@ package org.openpilot.androidgcs; import android.appwidget.AppWidgetManager; import android.appwidget.AppWidgetProvider; +import android.content.ComponentName; import android.content.Context; +import android.content.Intent; import android.widget.RemoteViews; public class TelemetryWidget extends AppWidgetProvider { + @Override + public void onReceive(Context context, Intent intent) { + if(intent.getAction().equals(OPTelemetryService.INTENT_ACTION_CONNECTED)) { + changeStatus(context, true); + } + if(intent.getAction().equals(OPTelemetryService.INTENT_ACTION_DISCONNECTED)) { + changeStatus(context, false); + } + + super.onReceive(context, intent); + } + + public void changeStatus(Context context, boolean status) { + RemoteViews updateViews = new RemoteViews(context.getPackageName(), R.layout.telemetry_widget); + updateViews.setTextViewText(R.id.telemetryWidgetStatus, "Connection status: " + status); + ComponentName thisWidget = new ComponentName(context, TelemetryWidget.class); + AppWidgetManager manager = AppWidgetManager.getInstance(context); + manager.updateAppWidget(thisWidget, updateViews); + + } + public void onUpdate(Context context, AppWidgetManager appWidgetManager, int[] appWidgetIds) { final int N = appWidgetIds.length; @@ -16,7 +39,6 @@ public class TelemetryWidget extends AppWidgetProvider { // Get the layout for the App Widget and attach an on-click listener to the button RemoteViews views = new RemoteViews(context.getPackageName(), R.layout.telemetry_widget); - //views.setOnClickPendingIntent(R.id.button, pendingIntent); // Tell the AppWidgetManager to perform an update on the current App Widget appWidgetManager.updateAppWidget(appWidgetId, views); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java index 4eca6ea82..d1d47aebb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -28,7 +28,7 @@ package org.openpilot.uavtalk.uavobjects; -import org.openpilot.uavtalk.uavobjects.*; +//import org.openpilot.uavtalk.uavobjects.*; import org.openpilot.uavtalk.UAVObjectManager; public class UAVObjectsInitialize { From b654d68ee64d6a353340f46c989821b4bcf23ec5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 23 Mar 2011 11:37:20 -0500 Subject: [PATCH 240/543] Cleaner editor interface --- androidgcs/default.properties | 2 +- androidgcs/res/layout/object_browser.xml | 3 +- androidgcs/res/layout/object_edit.xml | 6 +- androidgcs/res/layout/object_editor.xml | 6 + androidgcs/res/values/strings.xml | 3 + .../androidgcs/OPTelemetryService.java | 5 +- .../openpilot/androidgcs/ObjectBrowser.java | 3 + .../openpilot/androidgcs/ObjectEditView.java | 114 ++++++++++++++++++ .../openpilot/androidgcs/ObjectEditor.java | 12 +- 9 files changed, 138 insertions(+), 16 deletions(-) create mode 100644 androidgcs/res/layout/object_editor.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java diff --git a/androidgcs/default.properties b/androidgcs/default.properties index 728f51f97..fd1cedd24 100644 --- a/androidgcs/default.properties +++ b/androidgcs/default.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=Google Inc.:Google APIs:11 +target=Google Inc.:Google APIs:10 diff --git a/androidgcs/res/layout/object_browser.xml b/androidgcs/res/layout/object_browser.xml index 880e276ff..9c7456915 100644 --- a/androidgcs/res/layout/object_browser.xml +++ b/androidgcs/res/layout/object_browser.xml @@ -2,5 +2,6 @@ - + + diff --git a/androidgcs/res/layout/object_edit.xml b/androidgcs/res/layout/object_edit.xml index 62a482be9..c161caa4c 100644 --- a/androidgcs/res/layout/object_edit.xml +++ b/androidgcs/res/layout/object_edit.xml @@ -3,7 +3,7 @@ xmlns:android="http://schemas.android.com/apk/res/android" android:layout_width="match_parent" android:layout_height="match_parent"> - - - + + + diff --git a/androidgcs/res/layout/object_editor.xml b/androidgcs/res/layout/object_editor.xml new file mode 100644 index 000000000..d93b1a097 --- /dev/null +++ b/androidgcs/res/layout/object_editor.xml @@ -0,0 +1,6 @@ + + + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 7cef563e7..6d69e4126 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -21,4 +21,7 @@ S W Connected + Update + Save + Send
diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index c2914f34a..ce90f5a48 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -74,7 +74,8 @@ public class OPTelemetryService extends Service { Toast.makeText(getApplicationContext(), "Attempting connection", Toast.LENGTH_SHORT).show(); terminate = false; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); - int connection_type = Integer.decode(prefs.getString("connection_type", "")); + //int connection_type = Integer.decode(prefs.getString("connection_type", "")); + int connection_type = 1; switch(connection_type) { case 0: // No connection return; @@ -128,7 +129,7 @@ public class OPTelemetryService extends Service { mServiceHandler = new ServiceHandler(mServiceLooper); SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); - if(prefs.getBoolean("autoconnect", false)) { + if(prefs.getBoolean("autoconnect", false) || true) { Toast.makeText(getApplicationContext(), "Should auto connect", Toast.LENGTH_SHORT); Message msg = mServiceHandler.obtainMessage(); msg.arg1 = MSG_CONNECT; diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index df2d114a4..a6ed177a2 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -17,6 +17,7 @@ import android.view.View; import android.widget.AdapterView; import android.widget.ArrayAdapter; import android.widget.ListView; +import android.widget.Spinner; import android.widget.Toast; import android.widget.AdapterView.OnItemClickListener; @@ -46,6 +47,8 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref setContentView(R.layout.object_browser); prefs = PreferenceManager.getDefaultSharedPreferences(this); prefs.registerOnSharedPreferenceChangeListener(this); + + Spinner objectFilter = (Spinner) findViewById(R.id.object_list_filter); } @Override diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java b/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java new file mode 100644 index 000000000..7b81ff18c --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java @@ -0,0 +1,114 @@ +package org.openpilot.androidgcs; + +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectField; + +import android.content.Context; +import android.util.AttributeSet; +import android.view.View; +import android.widget.EditText; +import android.widget.LinearLayout; +import android.widget.TextView; + +public class ObjectEditView extends LinearLayout { + + TextView objectName; + List fields; + + public ObjectEditView(Context context) { + super(context); + initObjectEditView(); + } + + public ObjectEditView(Context context, AttributeSet ats, int defaultStyle) { + super(context, ats); + initObjectEditView(); + } + + public ObjectEditView(Context context, AttributeSet ats) { + super(context, ats); + initObjectEditView(); + } + + public void initObjectEditView() { + // Set orientation of layout to vertical + setOrientation(LinearLayout.VERTICAL); + + objectName = new TextView(getContext()); + objectName.setText(""); + objectName.setTextSize(14); + + // Lay them out in the compound control. + int lHeight = LayoutParams.WRAP_CONTENT; + int lWidth = LayoutParams.FILL_PARENT; + addView(objectName, new LinearLayout.LayoutParams(lWidth, lHeight)); + + fields = new ArrayList(); + } + + public void setName(String name) { + objectName.setText(name); + } + + public void addField(UAVObjectField field) { + if(field.getNumElements() == 1) { + FieldValue fieldView = new FieldValue(getContext()); + fieldView.setName(field.getName()); + if(field.isNumeric()) { + fieldView.setValue(new Double(field.getDouble()).toString()); + } else { + fieldView.setValue(field.getValue().toString()); + } + fields.add(fieldView); + addView(fieldView, new LinearLayout.LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.FILL_PARENT)); + } + else { + ListIterator names = field.getElementNames().listIterator(); + int i = 0; + while(names.hasNext()) { + FieldValue fieldView = new FieldValue(getContext()); + fieldView.setName(field.getName() + "-" + names.next()); + if(field.isNumeric()) { + fieldView.setValue(new Double(field.getDouble(i)).toString()); + } else { + fieldView.setValue(field.getValue(i).toString()); + } + i++; + fields.add(fieldView); + addView(fieldView, new LinearLayout.LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.FILL_PARENT)); + + } + } + } + + public class FieldValue extends LinearLayout { + + TextView fieldName; + EditText fieldValue; + + public FieldValue(Context context) { + super(context); + setOrientation(LinearLayout.HORIZONTAL); + + fieldName = new TextView(getContext()); + fieldValue = new EditText(getContext()); + + // Lay them out in the compound control. + addView(fieldName, new LinearLayout.LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.FILL_PARENT)); + fieldValue.setWidth(300); + addView(fieldValue, new LinearLayout.LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.WRAP_CONTENT)); + } + + public void setName(String name) { + fieldName.setText(name); + } + + public void setValue(String value) { + fieldValue.setText(value); + } + } + +} diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java b/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java index 33d0e2f8e..afbddb5e5 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectEditor.java @@ -7,8 +7,6 @@ import org.openpilot.uavtalk.UAVObject; import org.openpilot.uavtalk.UAVObjectField; import android.os.Bundle; -import android.widget.LinearLayout; -import android.widget.TextView; import android.widget.Toast; public class ObjectEditor extends ObjectManagerActivity { @@ -35,17 +33,13 @@ public class ObjectEditor extends ObjectManagerActivity { UAVObject obj = objMngr.getObject(objectID, instID); Toast.makeText(getApplicationContext(), obj.toString(), Toast.LENGTH_SHORT); - TextView objectName = (TextView) findViewById(R.id.object_edit_name); - objectName.setText(obj.getName()); + ObjectEditView editView = (ObjectEditView) findViewById(R.id.object_edit_view); + editView.setName(obj.getName()); - LinearLayout fieldViewList = (LinearLayout) findViewById(R.id.object_edit_fields); List fields = obj.getFields(); ListIterator li = fields.listIterator(); while(li.hasNext()) { - UAVObjectField field = li.next(); - TextView fieldName = new TextView(this); - fieldName.setText(field.getName()); - fieldViewList.addView(fieldName); + editView.addField(li.next()); } } From 723bcddc110c252cc5024ed8fbc59910cccf472b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Feb 2012 17:07:27 -0600 Subject: [PATCH 241/543] Update the project and checked in the meta data. Hopefully this will make it run more easily in future. --- androidgcs/.classpath | 8 +- androidgcs/.metadata/.lock | 0 androidgcs/.metadata/.log | 83 ++++ .../.metadata/.mylyn/repositories.xml.zip | Bin 0 -> 403 bytes androidgcs/.metadata/.mylyn/tasks.xml.zip | Bin 0 -> 250 bytes .../.plugins/org.eclipse.cdt.core/.log | 1 + .../.root/.indexes/history.version | 1 + .../.root/.indexes/properties.index | Bin 0 -> 57 bytes .../.root/.indexes/properties.version | 1 + .../org.eclipse.core.resources/.root/2.tree | Bin 0 -> 149 bytes .../.safetable/org.eclipse.core.resources | Bin 0 -> 614 bytes .../.settings/org.eclipse.cdt.ui.prefs | 5 + .../org.eclipse.core.resources.prefs | 3 + .../org.eclipse.epp.usagedata.recording.prefs | 3 + .../.settings/org.eclipse.jdt.ui.prefs | 15 + .../org.eclipse.mylyn.context.core.prefs | 3 + .../.settings/org.eclipse.team.cvs.ui.prefs | 3 + .../.settings/org.eclipse.team.ui.prefs | 3 + .../.settings/org.eclipse.ui.editors.prefs | 3 + .../.settings/org.eclipse.ui.ide.prefs | 5 + .../.settings/org.eclipse.ui.prefs | 3 + .../.settings/org.eclipse.ui.workbench.prefs | 3 + .../upload0.csv | 251 +++++++++++++ .../usagedata.csv | 83 ++++ .../org.eclipse.jdt.core/nonChainingJarsCache | Bin 0 -> 4 bytes .../variablesAndContainers.dat | Bin 0 -> 96 bytes .../org.eclipse.jdt.ui/OpenTypeHistory.xml | 2 + .../QualifiedTypeNameHistory.xml | 2 + .../org.eclipse.jdt.ui/dialog_settings.xml | 10 + .../org.eclipse.ui.ide/dialog_settings.xml | 9 + .../org.eclipse.ui.intro/dialog_settings.xml | 4 + .../dialog_settings.xml | 5 + .../org.eclipse.ui.workbench/workbench.xml | 355 ++++++++++++++++++ .../org.eclipse.ui.workbench/workingsets.xml | 4 + androidgcs/.metadata/version.ini | 1 + .../.settings/org.eclipse.jdt.core.prefs | 11 +- androidgcs/lint.xml | 3 + ...{default.properties => project.properties} | 4 +- 38 files changed, 879 insertions(+), 8 deletions(-) create mode 100644 androidgcs/.metadata/.lock create mode 100644 androidgcs/.metadata/.log create mode 100644 androidgcs/.metadata/.mylyn/repositories.xml.zip create mode 100644 androidgcs/.metadata/.mylyn/tasks.xml.zip create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.cdt.core/.log create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/history.version create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/properties.index create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/properties.version create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/2.tree create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.resources/.safetable/org.eclipse.core.resources create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.cdt.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.core.resources.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.epp.usagedata.recording.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.jdt.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.mylyn.context.core.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.cvs.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.editors.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.ide.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.workbench.prefs create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/upload0.csv create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/usagedata.csv create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.core/nonChainingJarsCache create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.core/variablesAndContainers.dat create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/OpenTypeHistory.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/QualifiedTypeNameHistory.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/dialog_settings.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.ide/dialog_settings.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.intro/dialog_settings.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/dialog_settings.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workbench.xml create mode 100644 androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workingsets.xml create mode 100644 androidgcs/.metadata/version.ini create mode 100644 androidgcs/lint.xml rename androidgcs/{default.properties => project.properties} (72%) diff --git a/androidgcs/.classpath b/androidgcs/.classpath index 6f3f456df..eb33e4360 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -1,9 +1,9 @@ + - - - - + + + diff --git a/androidgcs/.metadata/.lock b/androidgcs/.metadata/.lock new file mode 100644 index 000000000..e69de29bb diff --git a/androidgcs/.metadata/.log b/androidgcs/.metadata/.log new file mode 100644 index 000000000..8955f7bbc --- /dev/null +++ b/androidgcs/.metadata/.log @@ -0,0 +1,83 @@ +!SESSION 2012-02-04 14:21:36.086 ----------------------------------------------- +eclipse.buildId=unknown +java.version=1.6.0_29 +java.vendor=Apple Inc. +BootLoader constants: OS=macosx, ARCH=x86_64, WS=cocoa, NL=en_US +Framework arguments: -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -keyring /Users/jcotton81/.eclipse_keyring -showlocation +Command-line arguments: -os macosx -ws cocoa -arch x86_64 -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -data /Users/jcotton81/Documents/Programming/OpenPilot/androidgcs -product org.eclipse.epp.package.cpp.product -keyring /Users/jcotton81/.eclipse_keyring -showlocation + +!ENTRY org.eclipse.core.net 1 0 2012-02-04 14:21:41.864 +!MESSAGE System property http.nonProxyHosts has been set to local|*.local|169.254/16|*.169.254/16 by an external source. This value will be overwritten using the values from the preferences + +!ENTRY org.eclipse.ui.intro.universal 4 0 2012-02-04 14:21:44.892 +!MESSAGE /Users/jcotton81/Documents/Programming/eclipse/Eclipse.app/Contents/MacOS/introData.xml (No such file or directory) +!STACK 0 +java.io.FileNotFoundException: /Users/jcotton81/Documents/Programming/eclipse/Eclipse.app/Contents/MacOS/introData.xml (No such file or directory) + at java.io.FileInputStream.open(Native Method) + at java.io.FileInputStream.(FileInputStream.java:120) + at java.io.FileInputStream.(FileInputStream.java:79) + at sun.net.www.protocol.file.FileURLConnection.connect(FileURLConnection.java:70) + at sun.net.www.protocol.file.FileURLConnection.getInputStream(FileURLConnection.java:161) + at com.sun.org.apache.xerces.internal.impl.XMLEntityManager.setupCurrentEntity(XMLEntityManager.java:653) + at com.sun.org.apache.xerces.internal.impl.XMLVersionDetector.determineDocVersion(XMLVersionDetector.java:186) + at com.sun.org.apache.xerces.internal.parsers.XML11Configuration.parse(XML11Configuration.java:772) + at com.sun.org.apache.xerces.internal.parsers.XML11Configuration.parse(XML11Configuration.java:737) + at com.sun.org.apache.xerces.internal.parsers.XMLParser.parse(XMLParser.java:119) + at com.sun.org.apache.xerces.internal.parsers.DOMParser.parse(DOMParser.java:235) + at com.sun.org.apache.xerces.internal.jaxp.DocumentBuilderImpl.parse(DocumentBuilderImpl.java:284) + at javax.xml.parsers.DocumentBuilder.parse(DocumentBuilder.java:180) + at org.eclipse.ui.internal.intro.universal.IntroData.parse(IntroData.java:159) + at org.eclipse.ui.internal.intro.universal.IntroData.initialize(IntroData.java:63) + at org.eclipse.ui.internal.intro.universal.IntroData.(IntroData.java:47) + at org.eclipse.ui.internal.intro.universal.CustomizationContentsArea.loadData(CustomizationContentsArea.java:624) + at org.eclipse.ui.internal.intro.universal.CustomizationContentsArea.addPages(CustomizationContentsArea.java:489) + at org.eclipse.ui.internal.intro.universal.CustomizationContentsArea.createContents(CustomizationContentsArea.java:453) + at org.eclipse.ui.internal.intro.universal.CustomizationDialog.createDialogArea(CustomizationDialog.java:44) + at org.eclipse.jface.dialogs.Dialog.createContents(Dialog.java:760) + at org.eclipse.jface.window.Window.create(Window.java:431) + at org.eclipse.jface.dialogs.Dialog.create(Dialog.java:1089) + at org.eclipse.jface.window.Window.open(Window.java:790) + at org.eclipse.ui.internal.intro.universal.CustomizeAction.run(CustomizeAction.java:35) + at org.eclipse.ui.internal.intro.universal.CustomizeAction.run(CustomizeAction.java:29) + at org.eclipse.jface.action.Action.runWithEvent(Action.java:498) + at org.eclipse.jface.action.ActionContributionItem.handleWidgetSelection(ActionContributionItem.java:584) + at org.eclipse.jface.action.ActionContributionItem.access$2(ActionContributionItem.java:501) + at org.eclipse.jface.action.ActionContributionItem$6.handleEvent(ActionContributionItem.java:452) + at org.eclipse.swt.widgets.EventTable.sendEvent(EventTable.java:84) + at org.eclipse.swt.widgets.Display.sendEvent(Display.java:3543) + at org.eclipse.swt.widgets.Widget.sendEvent(Widget.java:1250) + at org.eclipse.swt.widgets.Widget.sendEvent(Widget.java:1273) + at org.eclipse.swt.widgets.Widget.sendEvent(Widget.java:1258) + at org.eclipse.swt.widgets.Widget.notifyListeners(Widget.java:1079) + at org.eclipse.swt.widgets.Display.runDeferredEvents(Display.java:3441) + at org.eclipse.swt.widgets.Display.readAndDispatch(Display.java:3100) + at org.eclipse.ui.internal.Workbench.runEventLoop(Workbench.java:2405) + at org.eclipse.ui.internal.Workbench.runUI(Workbench.java:2369) + at org.eclipse.ui.internal.Workbench.access$4(Workbench.java:2221) + at org.eclipse.ui.internal.Workbench$5.run(Workbench.java:500) + at org.eclipse.core.databinding.observable.Realm.runWithDefault(Realm.java:332) + at org.eclipse.ui.internal.Workbench.createAndRunWorkbench(Workbench.java:493) + at org.eclipse.ui.PlatformUI.createAndRunWorkbench(PlatformUI.java:149) + at org.eclipse.ui.internal.ide.application.IDEApplication.start(IDEApplication.java:113) + at org.eclipse.equinox.internal.app.EclipseAppHandle.run(EclipseAppHandle.java:194) + at org.eclipse.core.runtime.internal.adaptor.EclipseAppLauncher.runApplication(EclipseAppLauncher.java:110) + at org.eclipse.core.runtime.internal.adaptor.EclipseAppLauncher.start(EclipseAppLauncher.java:79) + at org.eclipse.core.runtime.adaptor.EclipseStarter.run(EclipseStarter.java:368) + at org.eclipse.core.runtime.adaptor.EclipseStarter.run(EclipseStarter.java:179) + at sun.reflect.NativeMethodAccessorImpl.invoke0(Native Method) + at sun.reflect.NativeMethodAccessorImpl.invoke(NativeMethodAccessorImpl.java:39) + at sun.reflect.DelegatingMethodAccessorImpl.invoke(DelegatingMethodAccessorImpl.java:25) + at java.lang.reflect.Method.invoke(Method.java:597) + at org.eclipse.equinox.launcher.Main.invokeFramework(Main.java:559) + at org.eclipse.equinox.launcher.Main.basicRun(Main.java:514) + at org.eclipse.equinox.launcher.Main.run(Main.java:1311) +!SESSION 2012-02-04 15:23:30.048 ----------------------------------------------- +eclipse.buildId=unknown +java.version=1.6.0_29 +java.vendor=Apple Inc. +BootLoader constants: OS=macosx, ARCH=x86_64, WS=cocoa, NL=en_US +Framework arguments: -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -keyring /Users/jcotton81/.eclipse_keyring -showlocation +Command-line arguments: -os macosx -ws cocoa -arch x86_64 -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -product org.eclipse.epp.package.cpp.product -data /Users/jcotton81/Documents/Programming/OpenPilot/androidgcs -product org.eclipse.epp.package.cpp.product -keyring /Users/jcotton81/.eclipse_keyring -showlocation + +!ENTRY org.eclipse.core.net 1 0 2012-02-04 15:23:34.575 +!MESSAGE System property http.nonProxyHosts has been set to local|*.local|169.254/16|*.169.254/16 by an external source. This value will be overwritten using the values from the preferences diff --git a/androidgcs/.metadata/.mylyn/repositories.xml.zip b/androidgcs/.metadata/.mylyn/repositories.xml.zip new file mode 100644 index 0000000000000000000000000000000000000000..e4df3bd3582f499f1a60b5def214b8ff52af6617 GIT binary patch literal 403 zcmWIWW@Zs#-~hsBMJ^5uNI(F{E=n!PFU~Bdj(; zVVO}bA}k9RU9H|_{jM!-va0dQyZ@?^bz^fywc_@+7(B7PS7R*c8`dl8&6Bbx*kFpf z!UfTNChLMenCzB(Vj$U{HcO2EMwQWWeBm$C<8L3AOn9FDyjhXMjCb8$XV&SwY{4(ytny2L z>Zr1KZsz5i=REypu2G!!Fu39-+x}N6Dmous-A{8_xY)$`S9N}$_2O##r|q}OnXHQb zs!#4`+gH4ys;~2NX}{PedAH=+g>TFBZddPTZ;$@K|4-sWx%33i%5DEskL3q=vvV9^ w68pi($iR@z%)k)f&B!FefCxZjIZyzi0`%Yv@MdKLsbB;`J0NWjG?jq?0GoN09smFU literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.mylyn/tasks.xml.zip b/androidgcs/.metadata/.mylyn/tasks.xml.zip new file mode 100644 index 0000000000000000000000000000000000000000..2c8620af394508c77be5ef0f6f867a56804938c0 GIT binary patch literal 250 zcmWIWW@Zs#-~dAIY8M9vB)|h?mn0Tv=VTU_=vCzAY~Hy3#MwX%Z(Xf(XU=a9HM(LP z5ae;z`<(yDGv3=nxp)gNZw(02(DOXw?RnEr%s1&+P<07Q|H{blRA2V9L+CH zm|nGXSgTK4vh2Bds8$6-=~ITSEzeY)TZ~o*1y2$ABUEh2^7U=bm&CMNj0^$Z>>R?m rvc?5KcT54|0B=Sn5e9@?k>x;cMFq$%5AbGX1IaQ1p%su`1y%|G7vM-E literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.cdt.core/.log b/androidgcs/.metadata/.plugins/org.eclipse.cdt.core/.log new file mode 100644 index 000000000..bce672614 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.cdt.core/.log @@ -0,0 +1 @@ +*** SESSION Feb 04, 2012 14:21:39.72 ------------------------------------------- diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/history.version b/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/history.version new file mode 100644 index 000000000..25cb955ba --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/history.version @@ -0,0 +1 @@ + \ No newline at end of file diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/properties.index b/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.root/.indexes/properties.index new file mode 100644 index 0000000000000000000000000000000000000000..9c245ea2cfab3511d0f8b7802966a5b2bb67b287 GIT binary patch literal 57 zcmZQ%U|?WmVAN+|WMUA>FG|--P0q4Yy oITE#s5Hp-2#a#t%!FeA{J(nSSiHf?N|MotxHB4MgVOxlqE}m~5?f?J) literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.safetable/org.eclipse.core.resources b/androidgcs/.metadata/.plugins/org.eclipse.core.resources/.safetable/org.eclipse.core.resources new file mode 100644 index 0000000000000000000000000000000000000000..f783b188fb03e942944121a16ffc8983afa430df GIT binary patch literal 614 zcmZ?R*xjhShe1S2b=vdAllRFf=Oz}Hq!uZZBqrsgaw!KVmMFNTCMg)0C>WYr8JPf) zf^%?)f{}rt5m$0fYGRQ~YEDUFe11{7UTShqWs%=_gPH`$%3P^!# zML}j!Vo7Fx9*WW|m{LPyBMW0o12Z!d14Bc+THvNbwU}6#8UwZ9a0}c5h+A-|%B{?) w%+o7LEY2?0E6s$uTVJoFC^gmAi0eSa@6X^M3jEwty}SIF!)TDD>X8;?0Hs9PH2?qr literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.cdt.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.cdt.ui.prefs new file mode 100644 index 000000000..3f144b036 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.cdt.ui.prefs @@ -0,0 +1,5 @@ +#Sat Feb 04 15:21:25 CST 2012 +spelling_locale_initialized=true +useAnnotationsPrefPage=true +eclipse.preferences.version=1 +useQuickDiffPrefPage=true diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.core.resources.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.core.resources.prefs new file mode 100644 index 000000000..360fc96b9 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.core.resources.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +version=1 +eclipse.preferences.version=1 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.epp.usagedata.recording.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.epp.usagedata.recording.prefs new file mode 100644 index 000000000..87706c344 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.epp.usagedata.recording.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 14:21:44 CST 2012 +org.eclipse.epp.usagedata.recording.last-upload=1328386904231 +eclipse.preferences.version=1 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.jdt.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.jdt.ui.prefs new file mode 100644 index 000000000..bdcfb11b5 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.jdt.ui.prefs @@ -0,0 +1,15 @@ +#Sat Feb 04 15:21:25 CST 2012 +useQuickDiffPrefPage=true +proposalOrderMigrated=true +tabWidthPropagated=true +content_assist_proposals_background=255,255,255 +org.eclipse.jdt.ui.javadoclocations.migrated=true +useAnnotationsPrefPage=true +org.eclipse.jface.textfont=1|Monaco|11.0|0|COCOA|1|; +org.eclipse.jdt.internal.ui.navigator.layout=2 +org.eclipse.jdt.ui.editor.tab.width= +org.eclipse.jdt.ui.formatterprofiles.version=11 +spelling_locale_initialized=true +eclipse.preferences.version=1 +content_assist_proposals_foreground=0,0,0 +fontPropagated=true diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.mylyn.context.core.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.mylyn.context.core.prefs new file mode 100644 index 000000000..7ea301b2d --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.mylyn.context.core.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 14:21:42 CST 2012 +eclipse.preferences.version=1 +mylyn.attention.migrated=true diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.cvs.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.cvs.ui.prefs new file mode 100644 index 000000000..62dee9f90 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.cvs.ui.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +pref_first_startup=false +eclipse.preferences.version=1 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.ui.prefs new file mode 100644 index 000000000..06b301613 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.team.ui.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +eclipse.preferences.version=1 +org.eclipse.team.ui.first_time=false diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.editors.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.editors.prefs new file mode 100644 index 000000000..90e1e2da9 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.editors.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +eclipse.preferences.version=1 +overviewRuler_migration=migrated_3.1 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.ide.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.ide.prefs new file mode 100644 index 000000000..b945f2889 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.ide.prefs @@ -0,0 +1,5 @@ +#Sat Feb 04 15:21:25 CST 2012 +eclipse.preferences.version=1 +tipsAndTricks=true +platformState=1328386704250 +PROBLEMS_FILTERS_MIGRATE=true diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.prefs new file mode 100644 index 000000000..a97c1c1ab --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 15:21:25 CST 2012 +eclipse.preferences.version=1 +showIntro=false diff --git a/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.workbench.prefs b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.workbench.prefs new file mode 100644 index 000000000..005c5e9bc --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.core.runtime/.settings/org.eclipse.ui.workbench.prefs @@ -0,0 +1,3 @@ +#Sat Feb 04 14:21:42 CST 2012 +eclipse.preferences.version=1 +ENABLED_DECORATORS=com.android.ide.eclipse.adt.project.FolderDecorator\:true,org.eclipse.cdt.ui.indexedFiles\:false,org.eclipse.jdt.ui.override.decorator\:true,org.eclipse.jdt.ui.interface.decorator\:false,org.eclipse.jdt.ui.buildpath.decorator\:true,org.eclipse.mylyn.context.ui.decorator.interest\:true,org.eclipse.mylyn.tasks.ui.decorators.task\:true,org.eclipse.mylyn.team.ui.changeset.decorator\:true,org.eclipse.team.cvs.ui.decorator\:true,org.eclipse.ui.LinkedResourceDecorator\:true,org.eclipse.ui.ContentTypeDecorator\:true, diff --git a/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/upload0.csv b/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/upload0.csv new file mode 100644 index 000000000..bc6540615 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/upload0.csv @@ -0,0 +1,251 @@ +what,kind,bundleId,bundleVersion,description,time +activated,perspective,org.eclipse.cdt.ui,,"org.eclipse.cdt.ui.CPerspective",1328386903139 +started,bundle,org.eclipse.osgi,3.5.2.R35x_v20100126,"org.eclipse.osgi",1328386903141 +started,bundle,org.eclipse.equinox.simpleconfigurator,1.0.101.R35x_v20090807-1100,"org.eclipse.equinox.simpleconfigurator",1328386903142 +started,bundle,com.ibm.icu,4.0.1.v20090822,"com.ibm.icu",1328386903143 +started,bundle,org.eclipse.cdt.core,5.1.2.201002161416,"org.eclipse.cdt.core",1328386903143 +started,bundle,org.eclipse.cdt.make.ui,6.0.1.201002161416,"org.eclipse.cdt.make.ui",1328386903144 +started,bundle,org.eclipse.cdt.ui,5.1.2.201002161416,"org.eclipse.cdt.ui",1328386903147 +started,bundle,org.eclipse.core.contenttype,3.4.1.R35x_v20090826-0451,"org.eclipse.core.contenttype",1328386903148 +started,bundle,org.eclipse.core.databinding.observable,1.2.0.M20090902-0800,"org.eclipse.core.databinding.observable",1328386903148 +started,bundle,org.eclipse.core.expressions,3.4.101.R35x_v20100209,"org.eclipse.core.expressions",1328386903149 +started,bundle,org.eclipse.core.filebuffers,3.5.0.v20090526-2000,"org.eclipse.core.filebuffers",1328386903149 +started,bundle,org.eclipse.core.filesystem,1.2.1.R35x_v20091203-1235,"org.eclipse.core.filesystem",1328386903150 +started,bundle,org.eclipse.core.jobs,3.4.100.v20090429-1800,"org.eclipse.core.jobs",1328386903151 +started,bundle,org.eclipse.core.net,1.2.1.r35x_20090812-1200,"org.eclipse.core.net",1328386903152 +started,bundle,org.eclipse.core.resources,3.5.2.R35x_v20091203-1235,"org.eclipse.core.resources",1328386903153 +started,bundle,org.eclipse.core.runtime,3.5.0.v20090525,"org.eclipse.core.runtime",1328386903153 +started,bundle,org.eclipse.core.runtime.compatibility,3.2.0.v20090413,"org.eclipse.core.runtime.compatibility",1328386903154 +started,bundle,org.eclipse.core.runtime.compatibility.auth,3.2.100.v20090413,"org.eclipse.core.runtime.compatibility.auth",1328386903154 +started,bundle,org.eclipse.ecf,3.0.0.v20090831-1906,"org.eclipse.ecf",1328386903155 +started,bundle,org.eclipse.ecf.filetransfer,3.0.0.v20090831-1906,"org.eclipse.ecf.filetransfer",1328386903155 +started,bundle,org.eclipse.ecf.identity,3.0.0.v20090831-1906,"org.eclipse.ecf.identity",1328386903156 +started,bundle,org.eclipse.ecf.provider.filetransfer,3.0.1.v20090831-1906,"org.eclipse.ecf.provider.filetransfer",1328386903157 +started,bundle,org.eclipse.ecf.provider.filetransfer.httpclient,3.0.1.v20090831-1906,"org.eclipse.ecf.provider.filetransfer.httpclient",1328386903158 +started,bundle,org.eclipse.epp.usagedata.gathering,1.1.1.R201001291118,"org.eclipse.epp.usagedata.gathering",1328386903159 +started,bundle,org.eclipse.epp.usagedata.recording,1.1.1.R201001291118,"org.eclipse.epp.usagedata.recording",1328386903161 +started,bundle,org.eclipse.equinox.app,1.2.1.R35x_v20091203,"org.eclipse.equinox.app",1328386903164 +started,bundle,org.eclipse.equinox.common,3.5.1.R35x_v20090807-1100,"org.eclipse.equinox.common",1328386903165 +started,bundle,org.eclipse.equinox.ds,1.1.1.R35x_v20090806,"org.eclipse.equinox.ds",1328386903166 +started,bundle,org.eclipse.equinox.frameworkadmin,1.0.100.v20090520-1905,"org.eclipse.equinox.frameworkadmin",1328386903166 +started,bundle,org.eclipse.equinox.frameworkadmin.equinox,1.0.101.R35x_v20091214,"org.eclipse.equinox.frameworkadmin.equinox",1328386903166 +started,bundle,org.eclipse.equinox.p2.core,1.0.101.R35x_v20090819,"org.eclipse.equinox.p2.core",1328386903167 +started,bundle,org.eclipse.equinox.p2.director,1.0.101.R35x_v20100112,"org.eclipse.equinox.p2.director",1328386903168 +started,bundle,org.eclipse.equinox.p2.directorywatcher,1.0.100.v20090525,"org.eclipse.equinox.p2.directorywatcher",1328386903168 +started,bundle,org.eclipse.equinox.p2.engine,1.0.102.R35x_v20091117,"org.eclipse.equinox.p2.engine",1328386903169 +started,bundle,org.eclipse.equinox.p2.exemplarysetup,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.exemplarysetup",1328386903169 +started,bundle,org.eclipse.equinox.p2.garbagecollector,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.garbagecollector",1328386903170 +started,bundle,org.eclipse.equinox.p2.metadata,1.0.101.R35x_v20100112,"org.eclipse.equinox.p2.metadata",1328386903170 +started,bundle,org.eclipse.equinox.p2.metadata.repository,1.0.101.R35x_v20090812,"org.eclipse.equinox.p2.metadata.repository",1328386903171 +started,bundle,org.eclipse.equinox.p2.reconciler.dropins,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.reconciler.dropins",1328386903171 +started,bundle,org.eclipse.equinox.p2.repository,1.0.1.R35x_v20100105,"org.eclipse.equinox.p2.repository",1328386903172 +started,bundle,org.eclipse.equinox.p2.ui.sdk.scheduler,1.0.0.v20090520-1905,"org.eclipse.equinox.p2.ui.sdk.scheduler",1328386903172 +started,bundle,org.eclipse.equinox.p2.updatechecker,1.1.0.v20090520-1905,"org.eclipse.equinox.p2.updatechecker",1328386903172 +started,bundle,org.eclipse.equinox.preferences,3.2.301.R35x_v20091117,"org.eclipse.equinox.preferences",1328386903175 +started,bundle,org.eclipse.equinox.registry,3.4.100.v20090520-1800,"org.eclipse.equinox.registry",1328386903176 +started,bundle,org.eclipse.equinox.security,1.0.100.v20090520-1800,"org.eclipse.equinox.security",1328386903177 +started,bundle,org.eclipse.equinox.simpleconfigurator.manipulator,1.0.101.R35x_v20100209,"org.eclipse.equinox.simpleconfigurator.manipulator",1328386903177 +started,bundle,org.eclipse.equinox.util,1.0.100.v20090520-1800,"org.eclipse.equinox.util",1328386903178 +started,bundle,org.eclipse.help,3.4.1.v20090805_35x,"org.eclipse.help",1328386903179 +started,bundle,org.eclipse.jface,3.5.2.M20100120-0800,"org.eclipse.jface",1328386903179 +started,bundle,org.eclipse.jsch.core,1.1.100.I20090430-0408,"org.eclipse.jsch.core",1328386903180 +started,bundle,org.eclipse.ltk.core.refactoring,3.5.0.v20090513-2000,"org.eclipse.ltk.core.refactoring",1328386903180 +started,bundle,org.eclipse.mylyn.bugzilla.core,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.core",1328386903181 +started,bundle,org.eclipse.mylyn.bugzilla.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.ui",1328386903181 +started,bundle,org.eclipse.mylyn.commons.net,3.2.0.v20090617-0100-e3x,"org.eclipse.mylyn.commons.net",1328386903182 +started,bundle,org.eclipse.mylyn.commons.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.commons.ui",1328386903183 +started,bundle,org.eclipse.mylyn.context.core,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.core",1328386903183 +started,bundle,org.eclipse.mylyn.context.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.ui",1328386903184 +started,bundle,org.eclipse.mylyn.monitor.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.monitor.ui",1328386903185 +started,bundle,org.eclipse.mylyn.tasks.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.ui",1328386903186 +started,bundle,org.eclipse.mylyn.team.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.team.ui",1328386903186 +started,bundle,org.eclipse.team.core,3.5.1.r35x_20100113-0800,"org.eclipse.team.core",1328386903187 +started,bundle,org.eclipse.team.cvs.core,3.3.200.I20090430-0408,"org.eclipse.team.cvs.core",1328386903188 +started,bundle,org.eclipse.team.cvs.ui,3.3.202.r35x_20090930-0800,"org.eclipse.team.cvs.ui",1328386903189 +started,bundle,org.eclipse.team.ui,3.5.0.I20090430-0408,"org.eclipse.team.ui",1328386903189 +started,bundle,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui",1328386903191 +started,bundle,org.eclipse.ui.console,3.4.0.v20090513,"org.eclipse.ui.console",1328386903191 +started,bundle,org.eclipse.ui.editors,3.5.0.v20090527-2000,"org.eclipse.ui.editors",1328386903195 +started,bundle,org.eclipse.ui.forms,3.4.1.v20090714_35x,"org.eclipse.ui.forms",1328386903196 +started,bundle,org.eclipse.ui.ide,3.5.2.M20100113-0800,"org.eclipse.ui.ide",1328386903198 +started,bundle,org.eclipse.ui.intro,3.3.2.v20100111_35x,"org.eclipse.ui.intro",1328386903198 +started,bundle,org.eclipse.ui.intro.universal,3.2.300.v20090526,"org.eclipse.ui.intro.universal",1328386903198 +started,bundle,org.eclipse.ui.navigator,3.4.2.M20100120-0800,"org.eclipse.ui.navigator",1328386903199 +started,bundle,org.eclipse.ui.navigator.resources,3.4.1.M20090826-0800,"org.eclipse.ui.navigator.resources",1328386903200 +started,bundle,org.eclipse.ui.net,1.2.1.r35x_20090812-1200,"org.eclipse.ui.net",1328386903200 +started,bundle,org.eclipse.ui.views,3.4.1.M20090826-0800,"org.eclipse.ui.views",1328386903201 +started,bundle,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"org.eclipse.ui.workbench",1328386903202 +started,bundle,org.eclipse.ui.workbench.texteditor,3.5.1.r352_v20100105,"org.eclipse.ui.workbench.texteditor",1328386903203 +started,bundle,org.eclipse.update.configurator,3.3.0.v20090312,"org.eclipse.update.configurator",1328386903207 +started,bundle,org.eclipse.update.core,3.2.300.v20090525,"org.eclipse.update.core",1328386903209 +started,bundle,org.eclipse.update.scheduler,3.2.200.v20081127,"org.eclipse.update.scheduler",1328386903210 +started,bundle,org.eclipse.jdt.core,3.5.2.v_981_R35x,"org.eclipse.jdt.core",1328386903211 +started,bundle,org.eclipse.jdt.core.manipulation,1.3.0.v20090603,"org.eclipse.jdt.core.manipulation",1328386903212 +started,bundle,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui",1328386903218 +os,sysinfo,,,"macosx",1328386903226 +arch,sysinfo,,,"x86_64",1328386903226 +ws,sysinfo,,,"cocoa",1328386903226 +locale,sysinfo,,,"en_US",1328386903226 +processors,sysinfo,,,"4",1328386903226 +java.runtime.name,sysinfo,,,"Java(TM) SE Runtime Environment",1328386903226 +java.runtime.version,sysinfo,,,"1.6.0_29-b11-402-11M3527",1328386903227 +java.specification.name,sysinfo,,,"Java Platform API Specification",1328386903227 +java.specification.vendor,sysinfo,,,"Sun Microsystems Inc.",1328386903227 +java.specification.version,sysinfo,,,"1.6",1328386903227 +java.vendor,sysinfo,,,"Apple Inc.",1328386903227 +java.version,sysinfo,,,"1.6.0_29",1328386903227 +java.vm.info,sysinfo,,,"mixed mode",1328386903227 +java.vm.name,sysinfo,,,"Java HotSpot(TM) 64-Bit Server VM",1328386903227 +java.vm.specification.name,sysinfo,,,"Java Virtual Machine Specification",1328386903227 +java.vm.specification.vendor,sysinfo,,,"Sun Microsystems Inc.",1328386903227 +java.vm.specification.version,sysinfo,,,"1.0",1328386903227 +java.vm.vendor,sysinfo,,,"Apple Inc.",1328386903227 +java.vm.version,sysinfo,,,"20.4-b02-402",1328386903227 +started,bundle,org.eclipse.equinox.p2.extensionlocation,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.extensionlocation",1328386903389 +started,bundle,org.eclipse.equinox.p2.artifact.repository,1.0.101.R35x_v20090721,"org.eclipse.equinox.p2.artifact.repository",1328386903414 +started,bundle,org.eclipse.equinox.p2.publisher,1.0.1.R35x_20100105,"org.eclipse.equinox.p2.publisher",1328386903450 +started,bundle,org.eclipse.equinox.p2.touchpoint.eclipse,1.0.101.R35x_20090820-1821,"org.eclipse.equinox.p2.touchpoint.eclipse",1328386903464 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328386903480 +activated,view,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.internal.introview",1328386903487 +error,log,,,"/Users/jcotton81/Documents/Programming/eclipse/Eclipse.app/Contents/MacOS/introData.xml (No such file or directory)",1328386904897 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328386905209 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328386906797 +started,bundle,org.eclipse.equinox.p2.updatesite,1.0.101.R35x_20100105,"org.eclipse.equinox.p2.updatesite",1328386912464 +activated,view,org.eclipse.ui.navigator.resources,3.4.1.M20090826-0800,"org.eclipse.ui.navigator.ProjectExplorer",1328386912583 +activated,view,org.eclipse.ui.navigator.resources,3.4.1.M20090826-0800,"org.eclipse.ui.navigator.ProjectExplorer",1328386912596 +closed,view,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.internal.introview",1328386912607 +started,bundle,org.eclipse.equinox.p2.ui,1.0.101.R35x_v20090819,"org.eclipse.equinox.p2.ui",1328386912856 +started,bundle,org.eclipse.equinox.p2.ui.sdk,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.ui.sdk",1328386912895 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328386920116 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328387108087 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328387114332 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328387670491 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328387680147 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328389984496 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328389985341 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390196855 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390210754 +started,bundle,com.android.ide.eclipse.ddms,10.0.1.v201103111512-110841,"com.android.ide.eclipse.ddms",1328390214192 +started,bundle,org.eclipse.wst.sse.core,1.1.402.v201001251516,"org.eclipse.wst.sse.core",1328390214246 +started,bundle,com.android.ide.eclipse.adt,10.0.1.v201103111512-110841,"com.android.ide.eclipse.adt",1328390214248 +started,bundle,org.eclipse.ltk.ui.refactoring,3.4.101.r352_v20100209,"org.eclipse.ltk.ui.refactoring",1328390214467 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390455517 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390462855 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390470613 +opened,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.PackageExplorer",1328390470944 +started,bundle,org.eclipse.search,3.5.1.r351_v20090708-0800,"org.eclipse.search",1328390471037 +opened,view,org.eclipse.mylyn.tasks.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.ui.views.tasks",1328390471127 +activated,perspective,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.JavaPerspective",1328390471151 +activated,view,org.eclipse.ui.ide,3.5.2.M20100113-0800,"org.eclipse.ui.views.ProblemView",1328390471175 +executed,command,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.perspectives.showPerspective",1328390471213 +executed,command,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.perspectives.showPerspective",1328390471213 +opened,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.JavadocView",1328390474490 +activated,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.JavadocView",1328390474500 +opened,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.SourceView",1328390475141 +activated,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.SourceView",1328390475161 +activated,view,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui.JavadocView",1328390475451 +activated,view,org.eclipse.ui.ide,3.5.2.M20100113-0800,"org.eclipse.ui.views.ProblemView",1328390475842 +closed,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390485206 +stopped,bundle,org.eclipse.cdt.debug.mi.ui,6.0.0.201002161416,"org.eclipse.cdt.debug.mi.ui",1328390485703 +stopped,bundle,org.eclipse.cdt.debug.gdbjtag.ui,5.0.100.201002161416,"org.eclipse.cdt.debug.gdbjtag.ui",1328390485704 +stopped,bundle,org.eclipse.cdt.debug.gdbjtag.core,5.0.100.201002161416,"org.eclipse.cdt.debug.gdbjtag.core",1328390485704 +stopped,bundle,org.eclipse.cdt.debug.mi.core,6.0.0.201002161416,"org.eclipse.cdt.debug.mi.core",1328390485705 +stopped,bundle,org.eclipse.cdt.dsf.gdb.ui,2.0.0.201002161416,"org.eclipse.cdt.dsf.gdb.ui",1328390485706 +stopped,bundle,org.eclipse.cdt.dsf.ui,2.0.1.201002161416,"org.eclipse.cdt.dsf.ui",1328390485707 +stopped,bundle,org.eclipse.cdt.launch,6.0.0.201002161416,"org.eclipse.cdt.launch",1328390485707 +stopped,bundle,org.eclipse.cdt.debug.ui,6.0.0.201002161416,"org.eclipse.cdt.debug.ui",1328390485708 +stopped,bundle,org.eclipse.cdt.dsf.gdb,2.0.0.201002161416,"org.eclipse.cdt.dsf.gdb",1328390485709 +stopped,bundle,org.eclipse.cdt.dsf,2.0.0.201002161416,"org.eclipse.cdt.dsf",1328390485709 +stopped,bundle,org.eclipse.cdt.debug.core,6.0.0.201002161416,"org.eclipse.cdt.debug.core",1328390485710 +stopped,bundle,org.eclipse.cdt.managedbuilder.ui,5.1.0.201002161416,"org.eclipse.cdt.managedbuilder.ui",1328390485710 +stopped,bundle,org.eclipse.cdt.make.ui,6.0.1.201002161416,"org.eclipse.cdt.make.ui",1328390485711 +stopped,bundle,org.eclipse.cdt.managedbuilder.gnu.ui,5.0.100.201002161416,"org.eclipse.cdt.managedbuilder.gnu.ui",1328390485711 +stopped,bundle,org.eclipse.cdt.managedbuilder.core,6.0.0.201002161416,"org.eclipse.cdt.managedbuilder.core",1328390485712 +stopped,bundle,org.eclipse.cdt.make.core,6.0.0.201002161416,"org.eclipse.cdt.make.core",1328390485713 +stopped,bundle,org.eclipse.cdt.mylyn.ui,1.0.100.201002161416,"org.eclipse.cdt.mylyn.ui",1328390485713 +stopped,bundle,org.eclipse.cdt.ui,5.1.2.201002161416,"org.eclipse.cdt.ui",1328390485713 +stopped,bundle,org.eclipse.cdt.core,5.1.2.201002161416,"org.eclipse.cdt.core",1328390485714 +stopped,bundle,org.eclipse.mylyn.bugzilla.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.ui",1328390485714 +stopped,bundle,org.eclipse.mylyn.ide.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.ide.ui",1328390485714 +stopped,bundle,org.eclipse.mylyn.team.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.team.ui",1328390485715 +stopped,bundle,org.eclipse.mylyn.resources.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.resources.ui",1328390485715 +stopped,bundle,org.eclipse.mylyn.wikitext.tasks.ui,1.1.3.v20100217-0100-e3x,"org.eclipse.mylyn.wikitext.tasks.ui",1328390485716 +stopped,bundle,org.eclipse.mylyn.context.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.ui",1328390485716 +stopped,bundle,org.eclipse.mylyn.help.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.help.ui",1328390485716 +stopped,bundle,org.eclipse.mylyn.tasks.bugs,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.bugs",1328390485717 +stopped,bundle,org.eclipse.mylyn.tasks.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.ui",1328390485719 +stopped,bundle,org.eclipse.ant.ui,3.4.2.v20091204_r352,"org.eclipse.ant.ui",1328390485719 +stopped,bundle,com.android.ide.eclipse.adt,10.0.1.v201103111512-110841,"com.android.ide.eclipse.adt",1328390485719 +stopped,bundle,org.eclipse.jdt.junit,3.5.2.r352_v20100113-0800,"org.eclipse.jdt.junit",1328390485720 +stopped,bundle,org.eclipse.jdt.debug.ui,3.4.1.v20090811_r351,"org.eclipse.jdt.debug.ui",1328390485721 +stopped,bundle,org.eclipse.jdt.apt.ui,3.3.200.v20090930-2100_R35x,"org.eclipse.jdt.apt.ui",1328390485722 +stopped,bundle,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui",1328390485726 +stopped,bundle,org.eclipse.wst.dtd.ui,1.0.400.v200904300717,"org.eclipse.wst.dtd.ui",1328390485730 +stopped,bundle,org.eclipse.wst.xsd.ui,1.2.204.v200909021537,"org.eclipse.wst.xsd.ui",1328390485747 +stopped,bundle,org.eclipse.wst.xml.ui,1.1.2.v201001222130,"org.eclipse.wst.xml.ui",1328390485747 +stopped,bundle,org.eclipse.wst.common.ui,1.1.402.v200901262305,"org.eclipse.wst.common.ui",1328390485748 +stopped,bundle,org.eclipse.wst.sse.ui,1.1.102.v200910200227,"org.eclipse.wst.sse.ui",1328390485749 +stopped,bundle,org.eclipse.search,3.5.1.r351_v20090708-0800,"org.eclipse.search",1328390485750 +stopped,bundle,org.eclipse.ltk.ui.refactoring,3.4.101.r352_v20100209,"org.eclipse.ltk.ui.refactoring",1328390485750 +stopped,bundle,org.eclipse.team.cvs.ui,3.3.202.r35x_20090930-0800,"org.eclipse.team.cvs.ui",1328390485751 +stopped,bundle,org.eclipse.team.ui,3.5.0.I20090430-0408,"org.eclipse.team.ui",1328390485751 +stopped,bundle,org.eclipse.compare,3.5.2.r35x_20100113-0800,"org.eclipse.compare",1328390485752 +stopped,bundle,org.eclipse.ui.externaltools,3.2.0.v20090504,"org.eclipse.ui.externaltools",1328390485753 +stopped,bundle,org.eclipse.debug.ui,3.5.2.v20091028_r352,"org.eclipse.debug.ui",1328390485756 +stopped,bundle,org.eclipse.mylyn.wikitext.ui,1.1.3.v20100217-0100-e3x,"org.eclipse.mylyn.wikitext.ui",1328390485757 +stopped,bundle,com.android.ide.eclipse.hierarchyviewer,10.0.1.v201103111512-110841,"com.android.ide.eclipse.hierarchyviewer",1328390485757 +stopped,bundle,com.android.ide.eclipse.ddms,10.0.1.v201103111512-110841,"com.android.ide.eclipse.ddms",1328390485757 +stopped,bundle,org.eclipse.ui.console,3.4.0.v20090513,"org.eclipse.ui.console",1328390485757 +stopped,bundle,org.eclipse.mylyn.commons.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.commons.ui",1328390485757 +stopped,bundle,org.eclipse.ui.editors,3.5.0.v20090527-2000,"org.eclipse.ui.editors",1328390485758 +stopped,bundle,org.eclipse.ui.navigator.resources,3.4.1.M20090826-0800,"org.eclipse.ui.navigator.resources",1328390485758 +activated,perspective,org.eclipse.jdt.ui,,"org.eclipse.jdt.ui.JavaPerspective",1328390616647 +started,bundle,org.eclipse.osgi,3.5.2.R35x_v20100126,"org.eclipse.osgi",1328390616648 +started,bundle,org.eclipse.equinox.simpleconfigurator,1.0.101.R35x_v20090807-1100,"org.eclipse.equinox.simpleconfigurator",1328390616653 +started,bundle,com.ibm.icu,4.0.1.v20090822,"com.ibm.icu",1328390616654 +started,bundle,org.eclipse.core.contenttype,3.4.1.R35x_v20090826-0451,"org.eclipse.core.contenttype",1328390616654 +started,bundle,org.eclipse.core.databinding.observable,1.2.0.M20090902-0800,"org.eclipse.core.databinding.observable",1328390616655 +started,bundle,org.eclipse.core.expressions,3.4.101.R35x_v20100209,"org.eclipse.core.expressions",1328390616656 +started,bundle,org.eclipse.core.filebuffers,3.5.0.v20090526-2000,"org.eclipse.core.filebuffers",1328390616656 +started,bundle,org.eclipse.core.jobs,3.4.100.v20090429-1800,"org.eclipse.core.jobs",1328390616656 +started,bundle,org.eclipse.core.net,1.2.1.r35x_20090812-1200,"org.eclipse.core.net",1328390616657 +started,bundle,org.eclipse.core.resources,3.5.2.R35x_v20091203-1235,"org.eclipse.core.resources",1328390616658 +started,bundle,org.eclipse.core.runtime,3.5.0.v20090525,"org.eclipse.core.runtime",1328390616659 +started,bundle,org.eclipse.core.runtime.compatibility,3.2.0.v20090413,"org.eclipse.core.runtime.compatibility",1328390616659 +started,bundle,org.eclipse.core.runtime.compatibility.auth,3.2.100.v20090413,"org.eclipse.core.runtime.compatibility.auth",1328390616660 +started,bundle,org.eclipse.ecf,3.0.0.v20090831-1906,"org.eclipse.ecf",1328390616660 +started,bundle,org.eclipse.ecf.filetransfer,3.0.0.v20090831-1906,"org.eclipse.ecf.filetransfer",1328390616661 +started,bundle,org.eclipse.ecf.identity,3.0.0.v20090831-1906,"org.eclipse.ecf.identity",1328390616662 +started,bundle,org.eclipse.ecf.provider.filetransfer,3.0.1.v20090831-1906,"org.eclipse.ecf.provider.filetransfer",1328390616663 +started,bundle,org.eclipse.ecf.provider.filetransfer.httpclient,3.0.1.v20090831-1906,"org.eclipse.ecf.provider.filetransfer.httpclient",1328390616663 +started,bundle,org.eclipse.epp.usagedata.gathering,1.1.1.R201001291118,"org.eclipse.epp.usagedata.gathering",1328390616664 +started,bundle,org.eclipse.epp.usagedata.recording,1.1.1.R201001291118,"org.eclipse.epp.usagedata.recording",1328390616668 +started,bundle,org.eclipse.equinox.app,1.2.1.R35x_v20091203,"org.eclipse.equinox.app",1328390616676 +started,bundle,org.eclipse.equinox.common,3.5.1.R35x_v20090807-1100,"org.eclipse.equinox.common",1328390616676 +started,bundle,org.eclipse.equinox.ds,1.1.1.R35x_v20090806,"org.eclipse.equinox.ds",1328390616677 +started,bundle,org.eclipse.equinox.frameworkadmin,1.0.100.v20090520-1905,"org.eclipse.equinox.frameworkadmin",1328390616679 +started,bundle,org.eclipse.equinox.frameworkadmin.equinox,1.0.101.R35x_v20091214,"org.eclipse.equinox.frameworkadmin.equinox",1328390616680 +started,bundle,org.eclipse.equinox.p2.core,1.0.101.R35x_v20090819,"org.eclipse.equinox.p2.core",1328390616681 +started,bundle,org.eclipse.equinox.p2.director,1.0.101.R35x_v20100112,"org.eclipse.equinox.p2.director",1328390616682 +started,bundle,org.eclipse.equinox.p2.directorywatcher,1.0.100.v20090525,"org.eclipse.equinox.p2.directorywatcher",1328390616688 +started,bundle,org.eclipse.equinox.p2.engine,1.0.102.R35x_v20091117,"org.eclipse.equinox.p2.engine",1328390616689 +started,bundle,org.eclipse.equinox.p2.exemplarysetup,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.exemplarysetup",1328390616690 +started,bundle,org.eclipse.equinox.p2.garbagecollector,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.garbagecollector",1328390616691 +started,bundle,org.eclipse.equinox.p2.metadata,1.0.101.R35x_v20100112,"org.eclipse.equinox.p2.metadata",1328390616692 +started,bundle,org.eclipse.equinox.p2.metadata.repository,1.0.101.R35x_v20090812,"org.eclipse.equinox.p2.metadata.repository",1328390616692 +started,bundle,org.eclipse.equinox.p2.reconciler.dropins,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.reconciler.dropins",1328390616693 +started,bundle,org.eclipse.equinox.p2.repository,1.0.1.R35x_v20100105,"org.eclipse.equinox.p2.repository",1328390616693 +started,bundle,org.eclipse.equinox.p2.ui.sdk.scheduler,1.0.0.v20090520-1905,"org.eclipse.equinox.p2.ui.sdk.scheduler",1328390616694 +started,bundle,org.eclipse.equinox.p2.updatechecker,1.1.0.v20090520-1905,"org.eclipse.equinox.p2.updatechecker",1328390616695 +started,bundle,org.eclipse.equinox.preferences,3.2.301.R35x_v20091117,"org.eclipse.equinox.preferences",1328390616695 +started,bundle,org.eclipse.equinox.registry,3.4.100.v20090520-1800,"org.eclipse.equinox.registry",1328390616696 +started,bundle,org.eclipse.equinox.security,1.0.100.v20090520-1800,"org.eclipse.equinox.security",1328390616697 +started,bundle,org.eclipse.equinox.simpleconfigurator.manipulator,1.0.101.R35x_v20100209,"org.eclipse.equinox.simpleconfigurator.manipulator",1328390616697 +started,bundle,org.eclipse.equinox.util,1.0.100.v20090520-1800,"org.eclipse.equinox.util",1328390616698 +started,bundle,org.eclipse.help,3.4.1.v20090805_35x,"org.eclipse.help",1328390616698 +started,bundle,org.eclipse.jface,3.5.2.M20100120-0800,"org.eclipse.jface",1328390616699 +started,bundle,org.eclipse.jsch.core,1.1.100.I20090430-0408,"org.eclipse.jsch.core",1328390616705 +started,bundle,org.eclipse.mylyn.bugzilla.core,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.core",1328390616705 +started,bundle,org.eclipse.mylyn.bugzilla.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.ui",1328390616706 +started,bundle,org.eclipse.mylyn.commons.net,3.2.0.v20090617-0100-e3x,"org.eclipse.mylyn.commons.net",1328390616706 +started,bundle,org.eclipse.mylyn.commons.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.commons.ui",1328390616707 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/usagedata.csv b/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/usagedata.csv new file mode 100644 index 000000000..510c72478 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.epp.usagedata.recording/usagedata.csv @@ -0,0 +1,83 @@ +what,kind,bundleId,bundleVersion,description,time +started,bundle,org.eclipse.mylyn.context.core,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.core",1328390616707 +started,bundle,org.eclipse.mylyn.context.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.ui",1328390616708 +started,bundle,org.eclipse.mylyn.monitor.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.monitor.ui",1328390616708 +started,bundle,org.eclipse.mylyn.tasks.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.tasks.ui",1328390616709 +started,bundle,org.eclipse.mylyn.team.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.team.ui",1328390616710 +started,bundle,org.eclipse.search,3.5.1.r351_v20090708-0800,"org.eclipse.search",1328390616711 +started,bundle,org.eclipse.team.core,3.5.1.r35x_20100113-0800,"org.eclipse.team.core",1328390616712 +started,bundle,org.eclipse.team.cvs.core,3.3.200.I20090430-0408,"org.eclipse.team.cvs.core",1328390616712 +started,bundle,org.eclipse.team.cvs.ui,3.3.202.r35x_20090930-0800,"org.eclipse.team.cvs.ui",1328390616713 +started,bundle,org.eclipse.team.ui,3.5.0.I20090430-0408,"org.eclipse.team.ui",1328390616714 +started,bundle,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui",1328390616715 +started,bundle,org.eclipse.ui.console,3.4.0.v20090513,"org.eclipse.ui.console",1328390616716 +started,bundle,org.eclipse.ui.editors,3.5.0.v20090527-2000,"org.eclipse.ui.editors",1328390616717 +started,bundle,org.eclipse.ui.forms,3.4.1.v20090714_35x,"org.eclipse.ui.forms",1328390616717 +started,bundle,org.eclipse.ui.ide,3.5.2.M20100113-0800,"org.eclipse.ui.ide",1328390616718 +started,bundle,org.eclipse.ui.net,1.2.1.r35x_20090812-1200,"org.eclipse.ui.net",1328390616719 +started,bundle,org.eclipse.ui.views,3.4.1.M20090826-0800,"org.eclipse.ui.views",1328390616720 +started,bundle,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"org.eclipse.ui.workbench",1328390616720 +started,bundle,org.eclipse.ui.workbench.texteditor,3.5.1.r352_v20100105,"org.eclipse.ui.workbench.texteditor",1328390616721 +started,bundle,org.eclipse.update.configurator,3.3.0.v20090312,"org.eclipse.update.configurator",1328390616722 +started,bundle,org.eclipse.update.core,3.2.300.v20090525,"org.eclipse.update.core",1328390616722 +started,bundle,org.eclipse.update.scheduler,3.2.200.v20081127,"org.eclipse.update.scheduler",1328390616723 +started,bundle,org.eclipse.jdt.core,3.5.2.v_981_R35x,"org.eclipse.jdt.core",1328390616724 +started,bundle,org.eclipse.jdt.core.manipulation,1.3.0.v20090603,"org.eclipse.jdt.core.manipulation",1328390616725 +started,bundle,org.eclipse.jdt.ui,3.5.2.r352_v20100106-0800,"org.eclipse.jdt.ui",1328390616730 +os,sysinfo,,,"macosx",1328390616740 +arch,sysinfo,,,"x86_64",1328390616740 +ws,sysinfo,,,"cocoa",1328390616740 +locale,sysinfo,,,"en_US",1328390616740 +processors,sysinfo,,,"4",1328390616740 +java.runtime.name,sysinfo,,,"Java(TM) SE Runtime Environment",1328390616740 +java.runtime.version,sysinfo,,,"1.6.0_29-b11-402-11M3527",1328390616740 +java.specification.name,sysinfo,,,"Java Platform API Specification",1328390616740 +java.specification.vendor,sysinfo,,,"Sun Microsystems Inc.",1328390616740 +java.specification.version,sysinfo,,,"1.6",1328390616740 +java.vendor,sysinfo,,,"Apple Inc.",1328390616740 +java.version,sysinfo,,,"1.6.0_29",1328390616740 +java.vm.info,sysinfo,,,"mixed mode",1328390616740 +java.vm.name,sysinfo,,,"Java HotSpot(TM) 64-Bit Server VM",1328390616740 +java.vm.specification.name,sysinfo,,,"Java Virtual Machine Specification",1328390616740 +java.vm.specification.vendor,sysinfo,,,"Sun Microsystems Inc.",1328390616740 +java.vm.specification.version,sysinfo,,,"1.0",1328390616740 +java.vm.vendor,sysinfo,,,"Apple Inc.",1328390616740 +java.vm.version,sysinfo,,,"20.4-b02-402",1328390616740 +started,bundle,org.eclipse.equinox.p2.extensionlocation,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.extensionlocation",1328390616768 +started,bundle,org.eclipse.equinox.p2.artifact.repository,1.0.101.R35x_v20090721,"org.eclipse.equinox.p2.artifact.repository",1328390616783 +started,bundle,org.eclipse.equinox.p2.publisher,1.0.1.R35x_20100105,"org.eclipse.equinox.p2.publisher",1328390616808 +started,bundle,org.eclipse.equinox.p2.touchpoint.eclipse,1.0.101.R35x_20090820-1821,"org.eclipse.equinox.p2.touchpoint.eclipse",1328390616820 +deactivated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390619481 +started,bundle,org.eclipse.equinox.p2.updatesite,1.0.101.R35x_20100105,"org.eclipse.equinox.p2.updatesite",1328390623001 +started,bundle,org.eclipse.equinox.p2.ui,1.0.101.R35x_v20090819,"org.eclipse.equinox.p2.ui",1328390623371 +started,bundle,org.eclipse.equinox.p2.ui.sdk,1.0.100.v20090520-1905,"org.eclipse.equinox.p2.ui.sdk",1328390623409 +started,bundle,org.eclipse.core.filesystem,1.2.1.R35x_v20091203-1235,"org.eclipse.core.filesystem",1328390630622 +activated,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390659248 +executed,command,org.eclipse.ui,3.5.2.M20100120-0800,"org.eclipse.ui.file.import",1328390659277 +closed,workbench,org.eclipse.ui.workbench,3.5.2.M20100113-0800,"",1328390663881 +stopped,bundle,org.eclipse.cdt.debug.mi.ui,6.0.0.201002161416,"org.eclipse.cdt.debug.mi.ui",1328390664441 +stopped,bundle,org.eclipse.cdt.debug.gdbjtag.ui,5.0.100.201002161416,"org.eclipse.cdt.debug.gdbjtag.ui",1328390664442 +stopped,bundle,org.eclipse.cdt.debug.gdbjtag.core,5.0.100.201002161416,"org.eclipse.cdt.debug.gdbjtag.core",1328390664442 +stopped,bundle,org.eclipse.cdt.debug.mi.core,6.0.0.201002161416,"org.eclipse.cdt.debug.mi.core",1328390664443 +stopped,bundle,org.eclipse.cdt.dsf.gdb.ui,2.0.0.201002161416,"org.eclipse.cdt.dsf.gdb.ui",1328390664443 +stopped,bundle,org.eclipse.cdt.dsf.ui,2.0.1.201002161416,"org.eclipse.cdt.dsf.ui",1328390664444 +stopped,bundle,org.eclipse.cdt.launch,6.0.0.201002161416,"org.eclipse.cdt.launch",1328390664445 +stopped,bundle,org.eclipse.cdt.debug.ui,6.0.0.201002161416,"org.eclipse.cdt.debug.ui",1328390664446 +stopped,bundle,org.eclipse.cdt.dsf.gdb,2.0.0.201002161416,"org.eclipse.cdt.dsf.gdb",1328390664446 +stopped,bundle,org.eclipse.cdt.dsf,2.0.0.201002161416,"org.eclipse.cdt.dsf",1328390664447 +stopped,bundle,org.eclipse.cdt.debug.core,6.0.0.201002161416,"org.eclipse.cdt.debug.core",1328390664448 +stopped,bundle,org.eclipse.cdt.managedbuilder.ui,5.1.0.201002161416,"org.eclipse.cdt.managedbuilder.ui",1328390664449 +stopped,bundle,org.eclipse.cdt.make.ui,6.0.1.201002161416,"org.eclipse.cdt.make.ui",1328390664452 +stopped,bundle,org.eclipse.cdt.managedbuilder.gnu.ui,5.0.100.201002161416,"org.eclipse.cdt.managedbuilder.gnu.ui",1328390664453 +stopped,bundle,org.eclipse.cdt.managedbuilder.core,6.0.0.201002161416,"org.eclipse.cdt.managedbuilder.core",1328390664454 +stopped,bundle,org.eclipse.cdt.make.core,6.0.0.201002161416,"org.eclipse.cdt.make.core",1328390664455 +stopped,bundle,org.eclipse.cdt.mylyn.ui,1.0.100.201002161416,"org.eclipse.cdt.mylyn.ui",1328390664455 +stopped,bundle,org.eclipse.cdt.ui,5.1.2.201002161416,"org.eclipse.cdt.ui",1328390664458 +stopped,bundle,org.eclipse.cdt.core,5.1.2.201002161416,"org.eclipse.cdt.core",1328390664459 +stopped,bundle,org.eclipse.mylyn.bugzilla.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.bugzilla.ui",1328390664460 +stopped,bundle,org.eclipse.mylyn.ide.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.ide.ui",1328390664460 +stopped,bundle,org.eclipse.mylyn.team.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.team.ui",1328390664460 +stopped,bundle,org.eclipse.mylyn.resources.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.resources.ui",1328390664461 +stopped,bundle,org.eclipse.mylyn.wikitext.tasks.ui,1.1.3.v20100217-0100-e3x,"org.eclipse.mylyn.wikitext.tasks.ui",1328390664461 +stopped,bundle,org.eclipse.mylyn.context.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.context.ui",1328390664462 +stopped,bundle,org.eclipse.mylyn.help.ui,3.2.3.v20100217-0100-e3x,"org.eclipse.mylyn.help.ui",1328390664462 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.core/nonChainingJarsCache b/androidgcs/.metadata/.plugins/org.eclipse.jdt.core/nonChainingJarsCache new file mode 100644 index 0000000000000000000000000000000000000000..593f4708db84ac8fd0f5cc47c634f38c013fe9e4 GIT binary patch literal 4 LcmZQzU|;|M00aO5 literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.core/variablesAndContainers.dat b/androidgcs/.metadata/.plugins/org.eclipse.jdt.core/variablesAndContainers.dat new file mode 100644 index 0000000000000000000000000000000000000000..3aea61cb8e5c86745251f85e5305774c8841c019 GIT binary patch literal 96 zcmZQzU|?c^09G)??iJ)39~|V&2;?y`aCwFLd4|M$`1`to1eh4Oq0&MA{vjX{W(KeZ SA5SL`kA;B`q5)_CL=yl}T@PLW literal 0 HcmV?d00001 diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/OpenTypeHistory.xml b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/OpenTypeHistory.xml new file mode 100644 index 000000000..a4ee3cbc9 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/OpenTypeHistory.xml @@ -0,0 +1,2 @@ + + diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/QualifiedTypeNameHistory.xml b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/QualifiedTypeNameHistory.xml new file mode 100644 index 000000000..9e390f501 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/QualifiedTypeNameHistory.xml @@ -0,0 +1,2 @@ + + diff --git a/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/dialog_settings.xml b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/dialog_settings.xml new file mode 100644 index 000000000..8bc608925 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.jdt.ui/dialog_settings.xml @@ -0,0 +1,10 @@ + +
+
+ + + + + +
+
diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.ide/dialog_settings.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.ide/dialog_settings.xml new file mode 100644 index 000000000..ab9bf177c --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.ide/dialog_settings.xml @@ -0,0 +1,9 @@ + +
+
+ + +
+
+
+
diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.intro/dialog_settings.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.intro/dialog_settings.xml new file mode 100644 index 000000000..f118f0213 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.intro/dialog_settings.xml @@ -0,0 +1,4 @@ + +
+ +
diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/dialog_settings.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/dialog_settings.xml new file mode 100644 index 000000000..5b583c4be --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/dialog_settings.xml @@ -0,0 +1,5 @@ + +
+
+
+
diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workbench.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workbench.xml new file mode 100644 index 000000000..931fd0157 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workbench.xml @@ -0,0 +1,355 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workingsets.xml b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workingsets.xml new file mode 100644 index 000000000..8daaf65a1 --- /dev/null +++ b/androidgcs/.metadata/.plugins/org.eclipse.ui.workbench/workingsets.xml @@ -0,0 +1,4 @@ + + + + \ No newline at end of file diff --git a/androidgcs/.metadata/version.ini b/androidgcs/.metadata/version.ini new file mode 100644 index 000000000..c51ff745b --- /dev/null +++ b/androidgcs/.metadata/version.ini @@ -0,0 +1 @@ +org.eclipse.core.runtime=1 \ No newline at end of file diff --git a/androidgcs/.settings/org.eclipse.jdt.core.prefs b/androidgcs/.settings/org.eclipse.jdt.core.prefs index f3fe4d6d6..a149e8e84 100644 --- a/androidgcs/.settings/org.eclipse.jdt.core.prefs +++ b/androidgcs/.settings/org.eclipse.jdt.core.prefs @@ -1,5 +1,12 @@ -#Tue Mar 01 01:16:25 CST 2011 +#Sat Feb 04 16:05:48 CST 2012 eclipse.preferences.version=1 +org.eclipse.jdt.core.compiler.codegen.inlineJsrBytecode=enabled org.eclipse.jdt.core.compiler.codegen.targetPlatform=1.5 -org.eclipse.jdt.core.compiler.compliance=1.5 +org.eclipse.jdt.core.compiler.codegen.unusedLocal=preserve +org.eclipse.jdt.core.compiler.compliance=1.6 +org.eclipse.jdt.core.compiler.debug.lineNumber=generate +org.eclipse.jdt.core.compiler.debug.localVariable=generate +org.eclipse.jdt.core.compiler.debug.sourceFile=generate +org.eclipse.jdt.core.compiler.problem.assertIdentifier=error +org.eclipse.jdt.core.compiler.problem.enumIdentifier=error org.eclipse.jdt.core.compiler.source=1.5 diff --git a/androidgcs/lint.xml b/androidgcs/lint.xml new file mode 100644 index 000000000..ee0eead5b --- /dev/null +++ b/androidgcs/lint.xml @@ -0,0 +1,3 @@ + + + \ No newline at end of file diff --git a/androidgcs/default.properties b/androidgcs/project.properties similarity index 72% rename from androidgcs/default.properties rename to androidgcs/project.properties index fd1cedd24..5d85d779c 100644 --- a/androidgcs/default.properties +++ b/androidgcs/project.properties @@ -4,8 +4,8 @@ # This file must be checked in Version Control Systems. # # To customize properties used by the Ant build system use, -# "build.properties", and override values to adapt the script to your +# "ant.properties", and override values to adapt the script to your # project structure. # Project target. -target=Google Inc.:Google APIs:10 +target=Google Inc.:Google APIs:13 From e1ba3d2e6311182491d3667c5cd456421ad9ef6a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Feb 2012 18:30:04 -0600 Subject: [PATCH 242/543] Update the UAVObjects to the version on next. At some point a make script should generate these and copy from build/uavobjects-synth/java to this directory automatically. Also make sure java objects use CamelCase --- .../uavtalk/uavobjects/AHRSCalibration.java | 51 +- .../uavtalk/uavobjects/AHRSSettings.java | 32 +- .../uavtalk/uavobjects/AccessoryDesired.java | 139 +++++ .../uavtalk/uavobjects/ActuatorCommand.java | 12 +- .../uavtalk/uavobjects/ActuatorDesired.java | 2 +- .../uavtalk/uavobjects/ActuatorSettings.java | 496 ++++++++++-------- .../uavtalk/uavobjects/AhrsStatus.java | 10 +- .../uavtalk/uavobjects/AttitudeActual.java | 4 +- .../uavtalk/uavobjects/AttitudeRaw.java | 24 +- .../uavtalk/uavobjects/AttitudeSettings.java | 68 ++- .../uavtalk/uavobjects/BaroAltitude.java | 2 +- .../uavtalk/uavobjects/CameraDesired.java | 147 ++++++ .../uavobjects/CameraStabSettings.java | 205 ++++++++ ...emetrySettings.java => FaultSettings.java} | 45 +- .../uavtalk/uavobjects/FirmwareIAPObj.java | 97 +--- .../uavobjects/FlightBatterySettings.java | 177 +++++++ .../uavobjects/FlightBatteryState.java | 2 +- .../uavtalk/uavobjects/FlightPlanControl.java | 2 +- .../uavobjects/FlightPlanSettings.java | 2 +- .../uavtalk/uavobjects/FlightPlanStatus.java | 35 +- .../uavtalk/uavobjects/FlightStatus.java | 155 ++++++ .../uavobjects/FlightTelemetryStats.java | 20 +- .../uavtalk/uavobjects/GCSReceiver.java | 144 +++++ .../uavtalk/uavobjects/GCSTelemetryStats.java | 20 +- .../uavtalk/uavobjects/GPSPosition.java | 28 +- .../uavtalk/uavobjects/GPSSatellites.java | 48 +- .../openpilot/uavtalk/uavobjects/GPSTime.java | 10 +- .../uavtalk/uavobjects/GuidanceSettings.java | 76 +-- .../uavtalk/uavobjects/HomeLocation.java | 23 +- .../uavtalk/uavobjects/HwSettings.java | 291 ++++++++++ .../uavtalk/uavobjects/I2CStats.java | 34 +- .../uavobjects/ManualControlCommand.java | 55 +- .../uavobjects/ManualControlSettings.java | 313 +++++------ .../uavtalk/uavobjects/MixerSettings.java | 161 +++++- .../uavtalk/uavobjects/MixerStatus.java | 2 +- .../uavtalk/uavobjects/NedAccel.java | 2 +- .../uavtalk/uavobjects/ObjectPersistence.java | 23 +- .../uavtalk/uavobjects/PositionActual.java | 2 +- .../uavtalk/uavobjects/PositionDesired.java | 2 +- .../uavtalk/uavobjects/RateDesired.java | 2 +- ...erySettings.java => ReceiverActivity.java} | 74 ++- .../uavtalk/uavobjects/SonarAltitude.java | 2 +- .../uavobjects/StabilizationDesired.java | 4 +- .../uavobjects/StabilizationSettings.java | 119 +++-- .../uavtalk/uavobjects/SystemAlarms.java | 8 +- .../uavtalk/uavobjects/SystemSettings.java | 9 +- .../uavtalk/uavobjects/SystemStats.java | 6 +- .../uavtalk/uavobjects/TaskInfo.java | 24 +- .../uavobjects/UAVObjectsInitialize.java | 13 +- .../uavtalk/uavobjects/VelocityActual.java | 2 +- .../uavtalk/uavobjects/VelocityDesired.java | 2 +- .../uavtalk/uavobjects/WatchdogStatus.java | 2 +- .../java/uavobjectgeneratorjava.cpp | 2 +- 53 files changed, 2363 insertions(+), 867 deletions(-) create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java rename androidgcs/src/org/openpilot/uavtalk/uavobjects/{TelemetrySettings.java => FaultSettings.java} (74%) create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java rename androidgcs/src/org/openpilot/uavtalk/uavobjects/{BatterySettings.java => ReceiverActivity.java} (61%) diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java index 922582398..47d42991e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java @@ -51,30 +51,29 @@ public class AHRSCalibration extends UAVDataObject { List fields = new ArrayList(); - List measure_varElemNames = new ArrayList(); - measure_varElemNames.add("0"); - List measure_varEnumOptions = new ArrayList(); - measure_varEnumOptions.add("SET"); - measure_varEnumOptions.add("MEASURE"); - fields.add( new UAVObjectField("measure_var", "", UAVObjectField.FieldType.ENUM, measure_varElemNames, measure_varEnumOptions) ); - List accel_biasElemNames = new ArrayList(); accel_biasElemNames.add("X"); accel_biasElemNames.add("Y"); accel_biasElemNames.add("Z"); - fields.add( new UAVObjectField("accel_bias", "m/s^2", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); + fields.add( new UAVObjectField("accel_bias", "m/s", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); List accel_scaleElemNames = new ArrayList(); accel_scaleElemNames.add("X"); accel_scaleElemNames.add("Y"); accel_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("accel_scale", "(m/s^2)/lsb", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); + fields.add( new UAVObjectField("accel_scale", "(m/s)/lsb", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); + + List accel_orthoElemNames = new ArrayList(); + accel_orthoElemNames.add("XY"); + accel_orthoElemNames.add("XZ"); + accel_orthoElemNames.add("YZ"); + fields.add( new UAVObjectField("accel_ortho", "scale", UAVObjectField.FieldType.FLOAT32, accel_orthoElemNames, null) ); List accel_varElemNames = new ArrayList(); accel_varElemNames.add("X"); accel_varElemNames.add("Y"); accel_varElemNames.add("Z"); - fields.add( new UAVObjectField("accel_var", "(m/s^2)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); + fields.add( new UAVObjectField("accel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); List gyro_biasElemNames = new ArrayList(); gyro_biasElemNames.add("X"); @@ -126,6 +125,13 @@ public class AHRSCalibration extends UAVDataObject { pos_varElemNames.add("0"); fields.add( new UAVObjectField("pos_var", "m^2", UAVObjectField.FieldType.FLOAT32, pos_varElemNames, null) ); + List measure_varElemNames = new ArrayList(); + measure_varElemNames.add("0"); + List measure_varEnumOptions = new ArrayList(); + measure_varEnumOptions.add("SET"); + measure_varEnumOptions.add("MEASURE"); + fields.add( new UAVObjectField("measure_var", "", UAVObjectField.FieldType.ENUM, measure_varElemNames, measure_varEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -171,19 +177,21 @@ public class AHRSCalibration extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("measure_var").setValue("SET"); getField("accel_bias").setValue(-73.5,0); getField("accel_bias").setValue(-73.5,1); getField("accel_bias").setValue(73.5,2); getField("accel_scale").setValue(0.0359,0); getField("accel_scale").setValue(0.0359,1); - getField("accel_scale").setValue(-0.0359,2); + getField("accel_scale").setValue(0.0359,2); + getField("accel_ortho").setValue(0,0); + getField("accel_ortho").setValue(0,1); + getField("accel_ortho").setValue(0,2); getField("accel_var").setValue(0.0005,0); getField("accel_var").setValue(0.0005,1); getField("accel_var").setValue(0.0005,2); - getField("gyro_bias").setValue(23,0); - getField("gyro_bias").setValue(-23,1); - getField("gyro_bias").setValue(23,2); + getField("gyro_bias").setValue(28,0); + getField("gyro_bias").setValue(-28,1); + getField("gyro_bias").setValue(28,2); getField("gyro_scale").setValue(-0.017,0); getField("gyro_scale").setValue(0.017,1); getField("gyro_scale").setValue(-0.017,2); @@ -196,14 +204,15 @@ public class AHRSCalibration extends UAVDataObject { getField("mag_bias").setValue(0,0); getField("mag_bias").setValue(0,1); getField("mag_bias").setValue(0,2); - getField("mag_scale").setValue(-2,0); - getField("mag_scale").setValue(-2,1); - getField("mag_scale").setValue(-2,2); + getField("mag_scale").setValue(1,0); + getField("mag_scale").setValue(1,1); + getField("mag_scale").setValue(1,2); getField("mag_var").setValue(50,0); getField("mag_var").setValue(50,1); getField("mag_var").setValue(50,2); - getField("vel_var").setValue(0.4); - getField("pos_var").setValue(0.4); + getField("vel_var").setValue(10); + getField("pos_var").setValue(0.04); + getField("measure_var").setValue("SET"); } @@ -232,7 +241,7 @@ public class AHRSCalibration extends UAVDataObject { } // Constants - protected static final int OBJID = 0x30101BB2; + protected static final int OBJID = 0xFD0EDFC4; protected static final String NAME = "AHRSCalibration"; protected static String DESCRIPTION = "Contains the calibration settings for the @ref AHRSCommsModule"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java index c49c04778..032dae775 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java @@ -51,6 +51,18 @@ public class AHRSSettings extends UAVDataObject { List fields = new ArrayList(); + List YawBiasElemNames = new ArrayList(); + YawBiasElemNames.add("0"); + fields.add( new UAVObjectField("YawBias", "", UAVObjectField.FieldType.FLOAT32, YawBiasElemNames, null) ); + + List PitchBiasElemNames = new ArrayList(); + PitchBiasElemNames.add("0"); + fields.add( new UAVObjectField("PitchBias", "", UAVObjectField.FieldType.FLOAT32, PitchBiasElemNames, null) ); + + List RollBiasElemNames = new ArrayList(); + RollBiasElemNames.add("0"); + fields.add( new UAVObjectField("RollBias", "", UAVObjectField.FieldType.FLOAT32, RollBiasElemNames, null) ); + List AlgorithmElemNames = new ArrayList(); AlgorithmElemNames.add("0"); List AlgorithmEnumOptions = new ArrayList(); @@ -75,18 +87,6 @@ public class AHRSSettings extends UAVDataObject { BiasCorrectedRawEnumOptions.add("FALSE"); fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); - List YawBiasElemNames = new ArrayList(); - YawBiasElemNames.add("0"); - fields.add( new UAVObjectField("YawBias", "", UAVObjectField.FieldType.FLOAT32, YawBiasElemNames, null) ); - - List PitchBiasElemNames = new ArrayList(); - PitchBiasElemNames.add("0"); - fields.add( new UAVObjectField("PitchBias", "", UAVObjectField.FieldType.FLOAT32, PitchBiasElemNames, null) ); - - List RollBiasElemNames = new ArrayList(); - RollBiasElemNames.add("0"); - fields.add( new UAVObjectField("RollBias", "", UAVObjectField.FieldType.FLOAT32, RollBiasElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -132,13 +132,13 @@ public class AHRSSettings extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("YawBias").setValue(0); + getField("PitchBias").setValue(0); + getField("RollBias").setValue(0); getField("Algorithm").setValue("INSGPS_INDOOR_NOMAG"); getField("Downsampling").setValue(20); getField("UpdatePeriod").setValue(1); getField("BiasCorrectedRaw").setValue("TRUE"); - getField("YawBias").setValue(0); - getField("PitchBias").setValue(0); - getField("RollBias").setValue(0); } @@ -167,7 +167,7 @@ public class AHRSSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0xDEFC5548; + protected static final int OBJID = 0xF8591ED8; protected static final String NAME = "AHRSSettings"; protected static String DESCRIPTION = "Settings for the @ref AHRSCommsModule to control the algorithm and what is updated"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java new file mode 100644 index 000000000..13c63dfdd --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java @@ -0,0 +1,139 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Desired Auxillary actuator settings. Comes from @ref ManualControlModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Desired Auxillary actuator settings. Comes from @ref ManualControlModule. + +generated from accessorydesired.xml + **/ +public class AccessoryDesired extends UAVDataObject { + + public AccessoryDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AccessoryValElemNames = new ArrayList(); + AccessoryValElemNames.add("0"); + fields.add( new UAVObjectField("AccessoryVal", "", UAVObjectField.FieldType.FLOAT32, AccessoryValElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AccessoryDesired obj = new AccessoryDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AccessoryDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (AccessoryDesired)(objMngr.getObject(AccessoryDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xC409985A; + protected static final String NAME = "AccessoryDesired"; + protected static String DESCRIPTION = "Desired Auxillary actuator settings. Comes from @ref ManualControlModule."; + protected static final boolean ISSINGLEINST = 0 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java index a5d6230ac..08f2ebefe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java @@ -60,16 +60,18 @@ public class ActuatorCommand extends UAVDataObject { ChannelElemNames.add("5"); ChannelElemNames.add("6"); ChannelElemNames.add("7"); + ChannelElemNames.add("8"); + ChannelElemNames.add("9"); fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.INT16, ChannelElemNames, null) ); - List UpdateTimeElemNames = new ArrayList(); - UpdateTimeElemNames.add("0"); - fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.UINT8, UpdateTimeElemNames, null) ); - List MaxUpdateTimeElemNames = new ArrayList(); MaxUpdateTimeElemNames.add("0"); fields.add( new UAVObjectField("MaxUpdateTime", "ms", UAVObjectField.FieldType.UINT16, MaxUpdateTimeElemNames, null) ); + List UpdateTimeElemNames = new ArrayList(); + UpdateTimeElemNames.add("0"); + fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.UINT8, UpdateTimeElemNames, null) ); + List NumFailedUpdatesElemNames = new ArrayList(); NumFailedUpdatesElemNames.add("0"); fields.add( new UAVObjectField("NumFailedUpdates", "", UAVObjectField.FieldType.UINT8, NumFailedUpdatesElemNames, null) ); @@ -147,7 +149,7 @@ public class ActuatorCommand extends UAVDataObject { } // Constants - protected static final int OBJID = 0xE8E077D8; + protected static final int OBJID = 0x5324CB8; protected static final String NAME = "ActuatorCommand"; protected static String DESCRIPTION = "Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java index b81ca29da..03ff1985c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java @@ -148,7 +148,7 @@ public class ActuatorDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD4516782; + protected static final int OBJID = 0xCA4BC4A4; protected static final String NAME = "ActuatorDesired"; protected static String DESCRIPTION = "Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java index 542b433d1..71b0bb49f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java @@ -51,202 +51,6 @@ public class ActuatorSettings extends UAVDataObject { List fields = new ArrayList(); - List FixedWingRoll1ElemNames = new ArrayList(); - FixedWingRoll1ElemNames.add("0"); - List FixedWingRoll1EnumOptions = new ArrayList(); - FixedWingRoll1EnumOptions.add("Channel1"); - FixedWingRoll1EnumOptions.add("Channel2"); - FixedWingRoll1EnumOptions.add("Channel3"); - FixedWingRoll1EnumOptions.add("Channel4"); - FixedWingRoll1EnumOptions.add("Channel5"); - FixedWingRoll1EnumOptions.add("Channel6"); - FixedWingRoll1EnumOptions.add("Channel7"); - FixedWingRoll1EnumOptions.add("Channel8"); - FixedWingRoll1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingRoll1", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll1ElemNames, FixedWingRoll1EnumOptions) ); - - List FixedWingRoll2ElemNames = new ArrayList(); - FixedWingRoll2ElemNames.add("0"); - List FixedWingRoll2EnumOptions = new ArrayList(); - FixedWingRoll2EnumOptions.add("Channel1"); - FixedWingRoll2EnumOptions.add("Channel2"); - FixedWingRoll2EnumOptions.add("Channel3"); - FixedWingRoll2EnumOptions.add("Channel4"); - FixedWingRoll2EnumOptions.add("Channel5"); - FixedWingRoll2EnumOptions.add("Channel6"); - FixedWingRoll2EnumOptions.add("Channel7"); - FixedWingRoll2EnumOptions.add("Channel8"); - FixedWingRoll2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingRoll2", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll2ElemNames, FixedWingRoll2EnumOptions) ); - - List FixedWingPitch1ElemNames = new ArrayList(); - FixedWingPitch1ElemNames.add("0"); - List FixedWingPitch1EnumOptions = new ArrayList(); - FixedWingPitch1EnumOptions.add("Channel1"); - FixedWingPitch1EnumOptions.add("Channel2"); - FixedWingPitch1EnumOptions.add("Channel3"); - FixedWingPitch1EnumOptions.add("Channel4"); - FixedWingPitch1EnumOptions.add("Channel5"); - FixedWingPitch1EnumOptions.add("Channel6"); - FixedWingPitch1EnumOptions.add("Channel7"); - FixedWingPitch1EnumOptions.add("Channel8"); - FixedWingPitch1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingPitch1", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch1ElemNames, FixedWingPitch1EnumOptions) ); - - List FixedWingPitch2ElemNames = new ArrayList(); - FixedWingPitch2ElemNames.add("0"); - List FixedWingPitch2EnumOptions = new ArrayList(); - FixedWingPitch2EnumOptions.add("Channel1"); - FixedWingPitch2EnumOptions.add("Channel2"); - FixedWingPitch2EnumOptions.add("Channel3"); - FixedWingPitch2EnumOptions.add("Channel4"); - FixedWingPitch2EnumOptions.add("Channel5"); - FixedWingPitch2EnumOptions.add("Channel6"); - FixedWingPitch2EnumOptions.add("Channel7"); - FixedWingPitch2EnumOptions.add("Channel8"); - FixedWingPitch2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingPitch2", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch2ElemNames, FixedWingPitch2EnumOptions) ); - - List FixedWingYawElemNames = new ArrayList(); - FixedWingYawElemNames.add("0"); - List FixedWingYawEnumOptions = new ArrayList(); - FixedWingYawEnumOptions.add("Channel1"); - FixedWingYawEnumOptions.add("Channel2"); - FixedWingYawEnumOptions.add("Channel3"); - FixedWingYawEnumOptions.add("Channel4"); - FixedWingYawEnumOptions.add("Channel5"); - FixedWingYawEnumOptions.add("Channel6"); - FixedWingYawEnumOptions.add("Channel7"); - FixedWingYawEnumOptions.add("Channel8"); - FixedWingYawEnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingYaw", "channel", UAVObjectField.FieldType.ENUM, FixedWingYawElemNames, FixedWingYawEnumOptions) ); - - List FixedWingThrottleElemNames = new ArrayList(); - FixedWingThrottleElemNames.add("0"); - List FixedWingThrottleEnumOptions = new ArrayList(); - FixedWingThrottleEnumOptions.add("Channel1"); - FixedWingThrottleEnumOptions.add("Channel2"); - FixedWingThrottleEnumOptions.add("Channel3"); - FixedWingThrottleEnumOptions.add("Channel4"); - FixedWingThrottleEnumOptions.add("Channel5"); - FixedWingThrottleEnumOptions.add("Channel6"); - FixedWingThrottleEnumOptions.add("Channel7"); - FixedWingThrottleEnumOptions.add("Channel8"); - FixedWingThrottleEnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingThrottle", "channel", UAVObjectField.FieldType.ENUM, FixedWingThrottleElemNames, FixedWingThrottleEnumOptions) ); - - List VTOLMotorNElemNames = new ArrayList(); - VTOLMotorNElemNames.add("0"); - List VTOLMotorNEnumOptions = new ArrayList(); - VTOLMotorNEnumOptions.add("Channel1"); - VTOLMotorNEnumOptions.add("Channel2"); - VTOLMotorNEnumOptions.add("Channel3"); - VTOLMotorNEnumOptions.add("Channel4"); - VTOLMotorNEnumOptions.add("Channel5"); - VTOLMotorNEnumOptions.add("Channel6"); - VTOLMotorNEnumOptions.add("Channel7"); - VTOLMotorNEnumOptions.add("Channel8"); - VTOLMotorNEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorN", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNElemNames, VTOLMotorNEnumOptions) ); - - List VTOLMotorNEElemNames = new ArrayList(); - VTOLMotorNEElemNames.add("0"); - List VTOLMotorNEEnumOptions = new ArrayList(); - VTOLMotorNEEnumOptions.add("Channel1"); - VTOLMotorNEEnumOptions.add("Channel2"); - VTOLMotorNEEnumOptions.add("Channel3"); - VTOLMotorNEEnumOptions.add("Channel4"); - VTOLMotorNEEnumOptions.add("Channel5"); - VTOLMotorNEEnumOptions.add("Channel6"); - VTOLMotorNEEnumOptions.add("Channel7"); - VTOLMotorNEEnumOptions.add("Channel8"); - VTOLMotorNEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorNE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNEElemNames, VTOLMotorNEEnumOptions) ); - - List VTOLMotorEElemNames = new ArrayList(); - VTOLMotorEElemNames.add("0"); - List VTOLMotorEEnumOptions = new ArrayList(); - VTOLMotorEEnumOptions.add("Channel1"); - VTOLMotorEEnumOptions.add("Channel2"); - VTOLMotorEEnumOptions.add("Channel3"); - VTOLMotorEEnumOptions.add("Channel4"); - VTOLMotorEEnumOptions.add("Channel5"); - VTOLMotorEEnumOptions.add("Channel6"); - VTOLMotorEEnumOptions.add("Channel7"); - VTOLMotorEEnumOptions.add("Channel8"); - VTOLMotorEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorEElemNames, VTOLMotorEEnumOptions) ); - - List VTOLMotorSEElemNames = new ArrayList(); - VTOLMotorSEElemNames.add("0"); - List VTOLMotorSEEnumOptions = new ArrayList(); - VTOLMotorSEEnumOptions.add("Channel1"); - VTOLMotorSEEnumOptions.add("Channel2"); - VTOLMotorSEEnumOptions.add("Channel3"); - VTOLMotorSEEnumOptions.add("Channel4"); - VTOLMotorSEEnumOptions.add("Channel5"); - VTOLMotorSEEnumOptions.add("Channel6"); - VTOLMotorSEEnumOptions.add("Channel7"); - VTOLMotorSEEnumOptions.add("Channel8"); - VTOLMotorSEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorSE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSEElemNames, VTOLMotorSEEnumOptions) ); - - List VTOLMotorSElemNames = new ArrayList(); - VTOLMotorSElemNames.add("0"); - List VTOLMotorSEnumOptions = new ArrayList(); - VTOLMotorSEnumOptions.add("Channel1"); - VTOLMotorSEnumOptions.add("Channel2"); - VTOLMotorSEnumOptions.add("Channel3"); - VTOLMotorSEnumOptions.add("Channel4"); - VTOLMotorSEnumOptions.add("Channel5"); - VTOLMotorSEnumOptions.add("Channel6"); - VTOLMotorSEnumOptions.add("Channel7"); - VTOLMotorSEnumOptions.add("Channel8"); - VTOLMotorSEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorS", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSElemNames, VTOLMotorSEnumOptions) ); - - List VTOLMotorSWElemNames = new ArrayList(); - VTOLMotorSWElemNames.add("0"); - List VTOLMotorSWEnumOptions = new ArrayList(); - VTOLMotorSWEnumOptions.add("Channel1"); - VTOLMotorSWEnumOptions.add("Channel2"); - VTOLMotorSWEnumOptions.add("Channel3"); - VTOLMotorSWEnumOptions.add("Channel4"); - VTOLMotorSWEnumOptions.add("Channel5"); - VTOLMotorSWEnumOptions.add("Channel6"); - VTOLMotorSWEnumOptions.add("Channel7"); - VTOLMotorSWEnumOptions.add("Channel8"); - VTOLMotorSWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorSW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSWElemNames, VTOLMotorSWEnumOptions) ); - - List VTOLMotorWElemNames = new ArrayList(); - VTOLMotorWElemNames.add("0"); - List VTOLMotorWEnumOptions = new ArrayList(); - VTOLMotorWEnumOptions.add("Channel1"); - VTOLMotorWEnumOptions.add("Channel2"); - VTOLMotorWEnumOptions.add("Channel3"); - VTOLMotorWEnumOptions.add("Channel4"); - VTOLMotorWEnumOptions.add("Channel5"); - VTOLMotorWEnumOptions.add("Channel6"); - VTOLMotorWEnumOptions.add("Channel7"); - VTOLMotorWEnumOptions.add("Channel8"); - VTOLMotorWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorWElemNames, VTOLMotorWEnumOptions) ); - - List VTOLMotorNWElemNames = new ArrayList(); - VTOLMotorNWElemNames.add("0"); - List VTOLMotorNWEnumOptions = new ArrayList(); - VTOLMotorNWEnumOptions.add("Channel1"); - VTOLMotorNWEnumOptions.add("Channel2"); - VTOLMotorNWEnumOptions.add("Channel3"); - VTOLMotorNWEnumOptions.add("Channel4"); - VTOLMotorNWEnumOptions.add("Channel5"); - VTOLMotorNWEnumOptions.add("Channel6"); - VTOLMotorNWEnumOptions.add("Channel7"); - VTOLMotorNWEnumOptions.add("Channel8"); - VTOLMotorNWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorNW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNWElemNames, VTOLMotorNWEnumOptions) ); - List ChannelUpdateFreqElemNames = new ArrayList(); ChannelUpdateFreqElemNames.add("0"); ChannelUpdateFreqElemNames.add("1"); @@ -263,6 +67,8 @@ public class ActuatorSettings extends UAVDataObject { ChannelMaxElemNames.add("5"); ChannelMaxElemNames.add("6"); ChannelMaxElemNames.add("7"); + ChannelMaxElemNames.add("8"); + ChannelMaxElemNames.add("9"); fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); List ChannelNeutralElemNames = new ArrayList(); @@ -274,6 +80,8 @@ public class ActuatorSettings extends UAVDataObject { ChannelNeutralElemNames.add("5"); ChannelNeutralElemNames.add("6"); ChannelNeutralElemNames.add("7"); + ChannelNeutralElemNames.add("8"); + ChannelNeutralElemNames.add("9"); fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); List ChannelMinElemNames = new ArrayList(); @@ -285,8 +93,250 @@ public class ActuatorSettings extends UAVDataObject { ChannelMinElemNames.add("5"); ChannelMinElemNames.add("6"); ChannelMinElemNames.add("7"); + ChannelMinElemNames.add("8"); + ChannelMinElemNames.add("9"); fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); + List FixedWingRoll1ElemNames = new ArrayList(); + FixedWingRoll1ElemNames.add("0"); + List FixedWingRoll1EnumOptions = new ArrayList(); + FixedWingRoll1EnumOptions.add("Channel1"); + FixedWingRoll1EnumOptions.add("Channel2"); + FixedWingRoll1EnumOptions.add("Channel3"); + FixedWingRoll1EnumOptions.add("Channel4"); + FixedWingRoll1EnumOptions.add("Channel5"); + FixedWingRoll1EnumOptions.add("Channel6"); + FixedWingRoll1EnumOptions.add("Channel7"); + FixedWingRoll1EnumOptions.add("Channel8"); + FixedWingRoll1EnumOptions.add("Channel9"); + FixedWingRoll1EnumOptions.add("Channel10"); + FixedWingRoll1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingRoll1", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll1ElemNames, FixedWingRoll1EnumOptions) ); + + List FixedWingRoll2ElemNames = new ArrayList(); + FixedWingRoll2ElemNames.add("0"); + List FixedWingRoll2EnumOptions = new ArrayList(); + FixedWingRoll2EnumOptions.add("Channel1"); + FixedWingRoll2EnumOptions.add("Channel2"); + FixedWingRoll2EnumOptions.add("Channel3"); + FixedWingRoll2EnumOptions.add("Channel4"); + FixedWingRoll2EnumOptions.add("Channel5"); + FixedWingRoll2EnumOptions.add("Channel6"); + FixedWingRoll2EnumOptions.add("Channel7"); + FixedWingRoll2EnumOptions.add("Channel8"); + FixedWingRoll2EnumOptions.add("Channel9"); + FixedWingRoll2EnumOptions.add("Channel10"); + FixedWingRoll2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingRoll2", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll2ElemNames, FixedWingRoll2EnumOptions) ); + + List FixedWingPitch1ElemNames = new ArrayList(); + FixedWingPitch1ElemNames.add("0"); + List FixedWingPitch1EnumOptions = new ArrayList(); + FixedWingPitch1EnumOptions.add("Channel1"); + FixedWingPitch1EnumOptions.add("Channel2"); + FixedWingPitch1EnumOptions.add("Channel3"); + FixedWingPitch1EnumOptions.add("Channel4"); + FixedWingPitch1EnumOptions.add("Channel5"); + FixedWingPitch1EnumOptions.add("Channel6"); + FixedWingPitch1EnumOptions.add("Channel7"); + FixedWingPitch1EnumOptions.add("Channel8"); + FixedWingPitch1EnumOptions.add("Channel9"); + FixedWingPitch1EnumOptions.add("Channel10"); + FixedWingPitch1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingPitch1", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch1ElemNames, FixedWingPitch1EnumOptions) ); + + List FixedWingPitch2ElemNames = new ArrayList(); + FixedWingPitch2ElemNames.add("0"); + List FixedWingPitch2EnumOptions = new ArrayList(); + FixedWingPitch2EnumOptions.add("Channel1"); + FixedWingPitch2EnumOptions.add("Channel2"); + FixedWingPitch2EnumOptions.add("Channel3"); + FixedWingPitch2EnumOptions.add("Channel4"); + FixedWingPitch2EnumOptions.add("Channel5"); + FixedWingPitch2EnumOptions.add("Channel6"); + FixedWingPitch2EnumOptions.add("Channel7"); + FixedWingPitch2EnumOptions.add("Channel8"); + FixedWingPitch2EnumOptions.add("Channel9"); + FixedWingPitch2EnumOptions.add("Channel10"); + FixedWingPitch2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingPitch2", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch2ElemNames, FixedWingPitch2EnumOptions) ); + + List FixedWingYaw1ElemNames = new ArrayList(); + FixedWingYaw1ElemNames.add("0"); + List FixedWingYaw1EnumOptions = new ArrayList(); + FixedWingYaw1EnumOptions.add("Channel1"); + FixedWingYaw1EnumOptions.add("Channel2"); + FixedWingYaw1EnumOptions.add("Channel3"); + FixedWingYaw1EnumOptions.add("Channel4"); + FixedWingYaw1EnumOptions.add("Channel5"); + FixedWingYaw1EnumOptions.add("Channel6"); + FixedWingYaw1EnumOptions.add("Channel7"); + FixedWingYaw1EnumOptions.add("Channel8"); + FixedWingYaw1EnumOptions.add("Channel9"); + FixedWingYaw1EnumOptions.add("Channel10"); + FixedWingYaw1EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingYaw1", "channel", UAVObjectField.FieldType.ENUM, FixedWingYaw1ElemNames, FixedWingYaw1EnumOptions) ); + + List FixedWingYaw2ElemNames = new ArrayList(); + FixedWingYaw2ElemNames.add("0"); + List FixedWingYaw2EnumOptions = new ArrayList(); + FixedWingYaw2EnumOptions.add("Channel1"); + FixedWingYaw2EnumOptions.add("Channel2"); + FixedWingYaw2EnumOptions.add("Channel3"); + FixedWingYaw2EnumOptions.add("Channel4"); + FixedWingYaw2EnumOptions.add("Channel5"); + FixedWingYaw2EnumOptions.add("Channel6"); + FixedWingYaw2EnumOptions.add("Channel7"); + FixedWingYaw2EnumOptions.add("Channel8"); + FixedWingYaw2EnumOptions.add("Channel9"); + FixedWingYaw2EnumOptions.add("Channel10"); + FixedWingYaw2EnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingYaw2", "channel", UAVObjectField.FieldType.ENUM, FixedWingYaw2ElemNames, FixedWingYaw2EnumOptions) ); + + List FixedWingThrottleElemNames = new ArrayList(); + FixedWingThrottleElemNames.add("0"); + List FixedWingThrottleEnumOptions = new ArrayList(); + FixedWingThrottleEnumOptions.add("Channel1"); + FixedWingThrottleEnumOptions.add("Channel2"); + FixedWingThrottleEnumOptions.add("Channel3"); + FixedWingThrottleEnumOptions.add("Channel4"); + FixedWingThrottleEnumOptions.add("Channel5"); + FixedWingThrottleEnumOptions.add("Channel6"); + FixedWingThrottleEnumOptions.add("Channel7"); + FixedWingThrottleEnumOptions.add("Channel8"); + FixedWingThrottleEnumOptions.add("Channel9"); + FixedWingThrottleEnumOptions.add("Channel10"); + FixedWingThrottleEnumOptions.add("None"); + fields.add( new UAVObjectField("FixedWingThrottle", "channel", UAVObjectField.FieldType.ENUM, FixedWingThrottleElemNames, FixedWingThrottleEnumOptions) ); + + List VTOLMotorNElemNames = new ArrayList(); + VTOLMotorNElemNames.add("0"); + List VTOLMotorNEnumOptions = new ArrayList(); + VTOLMotorNEnumOptions.add("Channel1"); + VTOLMotorNEnumOptions.add("Channel2"); + VTOLMotorNEnumOptions.add("Channel3"); + VTOLMotorNEnumOptions.add("Channel4"); + VTOLMotorNEnumOptions.add("Channel5"); + VTOLMotorNEnumOptions.add("Channel6"); + VTOLMotorNEnumOptions.add("Channel7"); + VTOLMotorNEnumOptions.add("Channel8"); + VTOLMotorNEnumOptions.add("Channel9"); + VTOLMotorNEnumOptions.add("Channel10"); + VTOLMotorNEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorN", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNElemNames, VTOLMotorNEnumOptions) ); + + List VTOLMotorNEElemNames = new ArrayList(); + VTOLMotorNEElemNames.add("0"); + List VTOLMotorNEEnumOptions = new ArrayList(); + VTOLMotorNEEnumOptions.add("Channel1"); + VTOLMotorNEEnumOptions.add("Channel2"); + VTOLMotorNEEnumOptions.add("Channel3"); + VTOLMotorNEEnumOptions.add("Channel4"); + VTOLMotorNEEnumOptions.add("Channel5"); + VTOLMotorNEEnumOptions.add("Channel6"); + VTOLMotorNEEnumOptions.add("Channel7"); + VTOLMotorNEEnumOptions.add("Channel8"); + VTOLMotorNEEnumOptions.add("Channel9"); + VTOLMotorNEEnumOptions.add("Channel10"); + VTOLMotorNEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorNE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNEElemNames, VTOLMotorNEEnumOptions) ); + + List VTOLMotorEElemNames = new ArrayList(); + VTOLMotorEElemNames.add("0"); + List VTOLMotorEEnumOptions = new ArrayList(); + VTOLMotorEEnumOptions.add("Channel1"); + VTOLMotorEEnumOptions.add("Channel2"); + VTOLMotorEEnumOptions.add("Channel3"); + VTOLMotorEEnumOptions.add("Channel4"); + VTOLMotorEEnumOptions.add("Channel5"); + VTOLMotorEEnumOptions.add("Channel6"); + VTOLMotorEEnumOptions.add("Channel7"); + VTOLMotorEEnumOptions.add("Channel8"); + VTOLMotorEEnumOptions.add("Channel9"); + VTOLMotorEEnumOptions.add("Channel10"); + VTOLMotorEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorEElemNames, VTOLMotorEEnumOptions) ); + + List VTOLMotorSEElemNames = new ArrayList(); + VTOLMotorSEElemNames.add("0"); + List VTOLMotorSEEnumOptions = new ArrayList(); + VTOLMotorSEEnumOptions.add("Channel1"); + VTOLMotorSEEnumOptions.add("Channel2"); + VTOLMotorSEEnumOptions.add("Channel3"); + VTOLMotorSEEnumOptions.add("Channel4"); + VTOLMotorSEEnumOptions.add("Channel5"); + VTOLMotorSEEnumOptions.add("Channel6"); + VTOLMotorSEEnumOptions.add("Channel7"); + VTOLMotorSEEnumOptions.add("Channel8"); + VTOLMotorSEEnumOptions.add("Channel9"); + VTOLMotorSEEnumOptions.add("Channel10"); + VTOLMotorSEEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorSE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSEElemNames, VTOLMotorSEEnumOptions) ); + + List VTOLMotorSElemNames = new ArrayList(); + VTOLMotorSElemNames.add("0"); + List VTOLMotorSEnumOptions = new ArrayList(); + VTOLMotorSEnumOptions.add("Channel1"); + VTOLMotorSEnumOptions.add("Channel2"); + VTOLMotorSEnumOptions.add("Channel3"); + VTOLMotorSEnumOptions.add("Channel4"); + VTOLMotorSEnumOptions.add("Channel5"); + VTOLMotorSEnumOptions.add("Channel6"); + VTOLMotorSEnumOptions.add("Channel7"); + VTOLMotorSEnumOptions.add("Channel8"); + VTOLMotorSEnumOptions.add("Channel9"); + VTOLMotorSEnumOptions.add("Channel10"); + VTOLMotorSEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorS", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSElemNames, VTOLMotorSEnumOptions) ); + + List VTOLMotorSWElemNames = new ArrayList(); + VTOLMotorSWElemNames.add("0"); + List VTOLMotorSWEnumOptions = new ArrayList(); + VTOLMotorSWEnumOptions.add("Channel1"); + VTOLMotorSWEnumOptions.add("Channel2"); + VTOLMotorSWEnumOptions.add("Channel3"); + VTOLMotorSWEnumOptions.add("Channel4"); + VTOLMotorSWEnumOptions.add("Channel5"); + VTOLMotorSWEnumOptions.add("Channel6"); + VTOLMotorSWEnumOptions.add("Channel7"); + VTOLMotorSWEnumOptions.add("Channel8"); + VTOLMotorSWEnumOptions.add("Channel9"); + VTOLMotorSWEnumOptions.add("Channel10"); + VTOLMotorSWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorSW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSWElemNames, VTOLMotorSWEnumOptions) ); + + List VTOLMotorWElemNames = new ArrayList(); + VTOLMotorWElemNames.add("0"); + List VTOLMotorWEnumOptions = new ArrayList(); + VTOLMotorWEnumOptions.add("Channel1"); + VTOLMotorWEnumOptions.add("Channel2"); + VTOLMotorWEnumOptions.add("Channel3"); + VTOLMotorWEnumOptions.add("Channel4"); + VTOLMotorWEnumOptions.add("Channel5"); + VTOLMotorWEnumOptions.add("Channel6"); + VTOLMotorWEnumOptions.add("Channel7"); + VTOLMotorWEnumOptions.add("Channel8"); + VTOLMotorWEnumOptions.add("Channel9"); + VTOLMotorWEnumOptions.add("Channel10"); + VTOLMotorWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorWElemNames, VTOLMotorWEnumOptions) ); + + List VTOLMotorNWElemNames = new ArrayList(); + VTOLMotorNWElemNames.add("0"); + List VTOLMotorNWEnumOptions = new ArrayList(); + VTOLMotorNWEnumOptions.add("Channel1"); + VTOLMotorNWEnumOptions.add("Channel2"); + VTOLMotorNWEnumOptions.add("Channel3"); + VTOLMotorNWEnumOptions.add("Channel4"); + VTOLMotorNWEnumOptions.add("Channel5"); + VTOLMotorNWEnumOptions.add("Channel6"); + VTOLMotorNWEnumOptions.add("Channel7"); + VTOLMotorNWEnumOptions.add("Channel8"); + VTOLMotorNWEnumOptions.add("Channel9"); + VTOLMotorNWEnumOptions.add("Channel10"); + VTOLMotorNWEnumOptions.add("None"); + fields.add( new UAVObjectField("VTOLMotorNW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNWElemNames, VTOLMotorNWEnumOptions) ); + List ChannelTypeElemNames = new ArrayList(); ChannelTypeElemNames.add("0"); ChannelTypeElemNames.add("1"); @@ -296,10 +346,13 @@ public class ActuatorSettings extends UAVDataObject { ChannelTypeElemNames.add("5"); ChannelTypeElemNames.add("6"); ChannelTypeElemNames.add("7"); + ChannelTypeElemNames.add("8"); + ChannelTypeElemNames.add("9"); List ChannelTypeEnumOptions = new ArrayList(); ChannelTypeEnumOptions.add("PWM"); ChannelTypeEnumOptions.add("MK"); ChannelTypeEnumOptions.add("ASTEC4"); + ChannelTypeEnumOptions.add("PWM Alarm Buzzer"); fields.add( new UAVObjectField("ChannelType", "", UAVObjectField.FieldType.ENUM, ChannelTypeElemNames, ChannelTypeEnumOptions) ); List ChannelAddrElemNames = new ArrayList(); @@ -311,8 +364,17 @@ public class ActuatorSettings extends UAVDataObject { ChannelAddrElemNames.add("5"); ChannelAddrElemNames.add("6"); ChannelAddrElemNames.add("7"); + ChannelAddrElemNames.add("8"); + ChannelAddrElemNames.add("9"); fields.add( new UAVObjectField("ChannelAddr", "", UAVObjectField.FieldType.UINT8, ChannelAddrElemNames, null) ); + List MotorsSpinWhileArmedElemNames = new ArrayList(); + MotorsSpinWhileArmedElemNames.add("0"); + List MotorsSpinWhileArmedEnumOptions = new ArrayList(); + MotorsSpinWhileArmedEnumOptions.add("FALSE"); + MotorsSpinWhileArmedEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("MotorsSpinWhileArmed", "", UAVObjectField.FieldType.ENUM, MotorsSpinWhileArmedElemNames, MotorsSpinWhileArmedEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -358,20 +420,6 @@ public class ActuatorSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("FixedWingRoll1").setValue("None"); - getField("FixedWingRoll2").setValue("None"); - getField("FixedWingPitch1").setValue("None"); - getField("FixedWingPitch2").setValue("None"); - getField("FixedWingYaw").setValue("None"); - getField("FixedWingThrottle").setValue("None"); - getField("VTOLMotorN").setValue("None"); - getField("VTOLMotorNE").setValue("None"); - getField("VTOLMotorE").setValue("None"); - getField("VTOLMotorSE").setValue("None"); - getField("VTOLMotorS").setValue("None"); - getField("VTOLMotorSW").setValue("None"); - getField("VTOLMotorW").setValue("None"); - getField("VTOLMotorNW").setValue("None"); getField("ChannelUpdateFreq").setValue(50,0); getField("ChannelUpdateFreq").setValue(50,1); getField("ChannelUpdateFreq").setValue(50,2); @@ -384,6 +432,8 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelMax").setValue(1000,5); getField("ChannelMax").setValue(1000,6); getField("ChannelMax").setValue(1000,7); + getField("ChannelMax").setValue(1000,8); + getField("ChannelMax").setValue(1000,9); getField("ChannelNeutral").setValue(1000,0); getField("ChannelNeutral").setValue(1000,1); getField("ChannelNeutral").setValue(1000,2); @@ -392,6 +442,8 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelNeutral").setValue(1000,5); getField("ChannelNeutral").setValue(1000,6); getField("ChannelNeutral").setValue(1000,7); + getField("ChannelNeutral").setValue(1000,8); + getField("ChannelNeutral").setValue(1000,9); getField("ChannelMin").setValue(1000,0); getField("ChannelMin").setValue(1000,1); getField("ChannelMin").setValue(1000,2); @@ -400,6 +452,23 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelMin").setValue(1000,5); getField("ChannelMin").setValue(1000,6); getField("ChannelMin").setValue(1000,7); + getField("ChannelMin").setValue(1000,8); + getField("ChannelMin").setValue(1000,9); + getField("FixedWingRoll1").setValue("None"); + getField("FixedWingRoll2").setValue("None"); + getField("FixedWingPitch1").setValue("None"); + getField("FixedWingPitch2").setValue("None"); + getField("FixedWingYaw1").setValue("None"); + getField("FixedWingYaw2").setValue("None"); + getField("FixedWingThrottle").setValue("None"); + getField("VTOLMotorN").setValue("None"); + getField("VTOLMotorNE").setValue("None"); + getField("VTOLMotorE").setValue("None"); + getField("VTOLMotorSE").setValue("None"); + getField("VTOLMotorS").setValue("None"); + getField("VTOLMotorSW").setValue("None"); + getField("VTOLMotorW").setValue("None"); + getField("VTOLMotorNW").setValue("None"); getField("ChannelType").setValue("PWM",0); getField("ChannelType").setValue("PWM",1); getField("ChannelType").setValue("PWM",2); @@ -408,6 +477,8 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelType").setValue("PWM",5); getField("ChannelType").setValue("PWM",6); getField("ChannelType").setValue("PWM",7); + getField("ChannelType").setValue("PWM",8); + getField("ChannelType").setValue("PWM",9); getField("ChannelAddr").setValue(0,0); getField("ChannelAddr").setValue(1,1); getField("ChannelAddr").setValue(2,2); @@ -416,6 +487,9 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelAddr").setValue(5,5); getField("ChannelAddr").setValue(6,6); getField("ChannelAddr").setValue(7,7); + getField("ChannelAddr").setValue(8,8); + getField("ChannelAddr").setValue(9,9); + getField("MotorsSpinWhileArmed").setValue("FALSE"); } @@ -444,7 +518,7 @@ public class ActuatorSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x1BF864C2; + protected static final int OBJID = 0xF2875746; protected static final String NAME = "ActuatorSettings"; protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java index 3ee8304ae..82e447a70 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java @@ -51,6 +51,10 @@ public class AhrsStatus extends UAVDataObject { List fields = new ArrayList(); + List RunningTimeElemNames = new ArrayList(); + RunningTimeElemNames.add("0"); + fields.add( new UAVObjectField("RunningTime", "ms", UAVObjectField.FieldType.UINT32, RunningTimeElemNames, null) ); + List SerialNumberElemNames = new ArrayList(); SerialNumberElemNames.add("0"); SerialNumberElemNames.add("1"); @@ -66,10 +70,6 @@ public class AhrsStatus extends UAVDataObject { CPULoadElemNames.add("0"); fields.add( new UAVObjectField("CPULoad", "count", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); - List RunningTimeElemNames = new ArrayList(); - RunningTimeElemNames.add("0"); - fields.add( new UAVObjectField("RunningTime", "ms", UAVObjectField.FieldType.UINT32, RunningTimeElemNames, null) ); - List IdleTimePerCyleElemNames = new ArrayList(); IdleTimePerCyleElemNames.add("0"); fields.add( new UAVObjectField("IdleTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, IdleTimePerCyleElemNames, null) ); @@ -190,7 +190,7 @@ public class AhrsStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x37A5F7A2; + protected static final int OBJID = 0x706D1AB8; protected static final String NAME = "AhrsStatus"; protected static String DESCRIPTION = "Status for the @ref AHRSCommsModule, including communication errors"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java index 714c18571..7c9272cad 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java @@ -110,7 +110,7 @@ public class AttitudeActual extends UAVDataObject { metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 500; + metadata.flightTelemetryUpdatePeriod = 100; metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; metadata.loggingUpdatePeriod = 0; @@ -152,7 +152,7 @@ public class AttitudeActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0xFC5B8CF4; + protected static final int OBJID = 0x33DAD5E6; protected static final String NAME = "AttitudeActual"; protected static String DESCRIPTION = "The updated Attitude estimation from @ref AHRSCommsModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java index d28302b6a..b8c3aacb4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java @@ -51,29 +51,29 @@ public class AttitudeRaw extends UAVDataObject { List fields = new ArrayList(); - List magnetometersElemNames = new ArrayList(); - magnetometersElemNames.add("X"); - magnetometersElemNames.add("Y"); - magnetometersElemNames.add("Z"); - fields.add( new UAVObjectField("magnetometers", "mGa", UAVObjectField.FieldType.INT16, magnetometersElemNames, null) ); - List gyrosElemNames = new ArrayList(); gyrosElemNames.add("X"); gyrosElemNames.add("Y"); gyrosElemNames.add("Z"); fields.add( new UAVObjectField("gyros", "deg/s", UAVObjectField.FieldType.FLOAT32, gyrosElemNames, null) ); - List gyrotempElemNames = new ArrayList(); - gyrotempElemNames.add("XY"); - gyrotempElemNames.add("Z"); - fields.add( new UAVObjectField("gyrotemp", "raw", UAVObjectField.FieldType.UINT16, gyrotempElemNames, null) ); - List accelsElemNames = new ArrayList(); accelsElemNames.add("X"); accelsElemNames.add("Y"); accelsElemNames.add("Z"); fields.add( new UAVObjectField("accels", "m/s^2", UAVObjectField.FieldType.FLOAT32, accelsElemNames, null) ); + List magnetometersElemNames = new ArrayList(); + magnetometersElemNames.add("X"); + magnetometersElemNames.add("Y"); + magnetometersElemNames.add("Z"); + fields.add( new UAVObjectField("magnetometers", "mGa", UAVObjectField.FieldType.INT16, magnetometersElemNames, null) ); + + List gyrotempElemNames = new ArrayList(); + gyrotempElemNames.add("XY"); + gyrotempElemNames.add("Z"); + fields.add( new UAVObjectField("gyrotemp", "raw", UAVObjectField.FieldType.UINT16, gyrotempElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -147,7 +147,7 @@ public class AttitudeRaw extends UAVDataObject { } // Constants - protected static final int OBJID = 0x37747DE6; + protected static final int OBJID = 0xDB722974; protected static final String NAME = "AttitudeRaw"; protected static String DESCRIPTION = "The raw attitude sensor data from @ref AHRSCommsModule. Not always updated."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java index 482fc12ce..3034a99ad 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java @@ -51,12 +51,6 @@ public class AttitudeSettings extends UAVDataObject { List fields = new ArrayList(); - List AccelBiasElemNames = new ArrayList(); - AccelBiasElemNames.add("X"); - AccelBiasElemNames.add("Y"); - AccelBiasElemNames.add("Z"); - fields.add( new UAVObjectField("AccelBias", "lsb", UAVObjectField.FieldType.INT16, AccelBiasElemNames, null) ); - List GyroGainElemNames = new ArrayList(); GyroGainElemNames.add("0"); fields.add( new UAVObjectField("GyroGain", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, GyroGainElemNames, null) ); @@ -69,6 +63,50 @@ public class AttitudeSettings extends UAVDataObject { AccelKiElemNames.add("0"); fields.add( new UAVObjectField("AccelKi", "channel", UAVObjectField.FieldType.FLOAT32, AccelKiElemNames, null) ); + List YawBiasRateElemNames = new ArrayList(); + YawBiasRateElemNames.add("0"); + fields.add( new UAVObjectField("YawBiasRate", "channel", UAVObjectField.FieldType.FLOAT32, YawBiasRateElemNames, null) ); + + List AccelBiasElemNames = new ArrayList(); + AccelBiasElemNames.add("X"); + AccelBiasElemNames.add("Y"); + AccelBiasElemNames.add("Z"); + fields.add( new UAVObjectField("AccelBias", "lsb", UAVObjectField.FieldType.INT16, AccelBiasElemNames, null) ); + + List GyroBiasElemNames = new ArrayList(); + GyroBiasElemNames.add("X"); + GyroBiasElemNames.add("Y"); + GyroBiasElemNames.add("Z"); + fields.add( new UAVObjectField("GyroBias", "deg/s * 100", UAVObjectField.FieldType.INT16, GyroBiasElemNames, null) ); + + List BoardRotationElemNames = new ArrayList(); + BoardRotationElemNames.add("Roll"); + BoardRotationElemNames.add("Pitch"); + BoardRotationElemNames.add("Yaw"); + fields.add( new UAVObjectField("BoardRotation", "deg", UAVObjectField.FieldType.INT16, BoardRotationElemNames, null) ); + + List ZeroDuringArmingElemNames = new ArrayList(); + ZeroDuringArmingElemNames.add("0"); + List ZeroDuringArmingEnumOptions = new ArrayList(); + ZeroDuringArmingEnumOptions.add("FALSE"); + ZeroDuringArmingEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("ZeroDuringArming", "channel", UAVObjectField.FieldType.ENUM, ZeroDuringArmingElemNames, ZeroDuringArmingEnumOptions) ); + + List BiasCorrectGyroElemNames = new ArrayList(); + BiasCorrectGyroElemNames.add("0"); + List BiasCorrectGyroEnumOptions = new ArrayList(); + BiasCorrectGyroEnumOptions.add("FALSE"); + BiasCorrectGyroEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("BiasCorrectGyro", "channel", UAVObjectField.FieldType.ENUM, BiasCorrectGyroElemNames, BiasCorrectGyroEnumOptions) ); + + List TrimFlightElemNames = new ArrayList(); + TrimFlightElemNames.add("0"); + List TrimFlightEnumOptions = new ArrayList(); + TrimFlightEnumOptions.add("NORMAL"); + TrimFlightEnumOptions.add("START"); + TrimFlightEnumOptions.add("LOAD"); + fields.add( new UAVObjectField("TrimFlight", "channel", UAVObjectField.FieldType.ENUM, TrimFlightElemNames, TrimFlightEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -114,12 +152,22 @@ public class AttitudeSettings extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("GyroGain").setValue(0.42); + getField("AccelKp").setValue(0.05); + getField("AccelKi").setValue(0.0001); + getField("YawBiasRate").setValue(1e-06); getField("AccelBias").setValue(0,0); getField("AccelBias").setValue(0,1); getField("AccelBias").setValue(0,2); - getField("GyroGain").setValue(0.42); - getField("AccelKp").setValue(0.01); - getField("AccelKi").setValue(0.0001); + getField("GyroBias").setValue(0,0); + getField("GyroBias").setValue(0,1); + getField("GyroBias").setValue(0,2); + getField("BoardRotation").setValue(0,0); + getField("BoardRotation").setValue(0,1); + getField("BoardRotation").setValue(0,2); + getField("ZeroDuringArming").setValue("TRUE"); + getField("BiasCorrectGyro").setValue("TRUE"); + getField("TrimFlight").setValue("NORMAL"); } @@ -148,7 +196,7 @@ public class AttitudeSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x327BF29A; + protected static final int OBJID = 0xC307BC4A; protected static final String NAME = "AttitudeSettings"; protected static String DESCRIPTION = "Settings for the @ref Attitude module used on CopterControl"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java index a2c2c7e3d..ecde53985 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java @@ -136,7 +136,7 @@ public class BaroAltitude extends UAVDataObject { } // Constants - protected static final int OBJID = 0xED4424F6; + protected static final int OBJID = 0x99622E6A; protected static final String NAME = "BaroAltitude"; protected static String DESCRIPTION = "The raw data from the barometric sensor with pressure, temperature and altitude estimate."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java new file mode 100644 index 000000000..7a36ec1ea --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java @@ -0,0 +1,147 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Desired camera outputs. Comes from @ref CameraStabilization module. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Desired camera outputs. Comes from @ref CameraStabilization module. + +generated from cameradesired.xml + **/ +public class CameraDesired extends UAVDataObject { + + public CameraDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; + metadata.flightTelemetryUpdatePeriod = 1000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + CameraDesired obj = new CameraDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public CameraDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (CameraDesired)(objMngr.getObject(CameraDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x531F544E; + protected static final String NAME = "CameraDesired"; + protected static String DESCRIPTION = "Desired camera outputs. Comes from @ref CameraStabilization module."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java new file mode 100644 index 000000000..a8e03df32 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java @@ -0,0 +1,205 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref CameraStab mmodule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref CameraStab mmodule + +generated from camerastabsettings.xml + **/ +public class CameraStabSettings extends UAVDataObject { + + public CameraStabSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List MaxAxisLockRateElemNames = new ArrayList(); + MaxAxisLockRateElemNames.add("0"); + fields.add( new UAVObjectField("MaxAxisLockRate", "deg/s", UAVObjectField.FieldType.FLOAT32, MaxAxisLockRateElemNames, null) ); + + List ResponseTimeElemNames = new ArrayList(); + ResponseTimeElemNames.add("Roll"); + ResponseTimeElemNames.add("Pitch"); + ResponseTimeElemNames.add("Yaw"); + fields.add( new UAVObjectField("ResponseTime", "ms", UAVObjectField.FieldType.UINT16, ResponseTimeElemNames, null) ); + + List InputElemNames = new ArrayList(); + InputElemNames.add("Roll"); + InputElemNames.add("Pitch"); + InputElemNames.add("Yaw"); + List InputEnumOptions = new ArrayList(); + InputEnumOptions.add("Accessory0"); + InputEnumOptions.add("Accessory1"); + InputEnumOptions.add("Accessory2"); + InputEnumOptions.add("Accessory3"); + InputEnumOptions.add("Accessory4"); + InputEnumOptions.add("Accessory5"); + InputEnumOptions.add("None"); + fields.add( new UAVObjectField("Input", "channel", UAVObjectField.FieldType.ENUM, InputElemNames, InputEnumOptions) ); + + List InputRangeElemNames = new ArrayList(); + InputRangeElemNames.add("Roll"); + InputRangeElemNames.add("Pitch"); + InputRangeElemNames.add("Yaw"); + fields.add( new UAVObjectField("InputRange", "deg", UAVObjectField.FieldType.UINT8, InputRangeElemNames, null) ); + + List InputRateElemNames = new ArrayList(); + InputRateElemNames.add("Roll"); + InputRateElemNames.add("Pitch"); + InputRateElemNames.add("Yaw"); + fields.add( new UAVObjectField("InputRate", "deg/s", UAVObjectField.FieldType.UINT8, InputRateElemNames, null) ); + + List StabilizationModeElemNames = new ArrayList(); + StabilizationModeElemNames.add("Roll"); + StabilizationModeElemNames.add("Pitch"); + StabilizationModeElemNames.add("Yaw"); + List StabilizationModeEnumOptions = new ArrayList(); + StabilizationModeEnumOptions.add("Attitude"); + StabilizationModeEnumOptions.add("AxisLock"); + fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); + + List OutputRangeElemNames = new ArrayList(); + OutputRangeElemNames.add("Roll"); + OutputRangeElemNames.add("Pitch"); + OutputRangeElemNames.add("Yaw"); + fields.add( new UAVObjectField("OutputRange", "deg", UAVObjectField.FieldType.UINT8, OutputRangeElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("MaxAxisLockRate").setValue(1); + getField("ResponseTime").setValue(150,0); + getField("ResponseTime").setValue(150,1); + getField("ResponseTime").setValue(150,2); + getField("Input").setValue("None",0); + getField("Input").setValue("None",1); + getField("Input").setValue("None",2); + getField("InputRange").setValue(20,0); + getField("InputRange").setValue(20,1); + getField("InputRange").setValue(20,2); + getField("InputRate").setValue(50,0); + getField("InputRate").setValue(50,1); + getField("InputRate").setValue(50,2); + getField("StabilizationMode").setValue("Attitude",0); + getField("StabilizationMode").setValue("Attitude",1); + getField("StabilizationMode").setValue("Attitude",2); + getField("OutputRange").setValue(20,0); + getField("OutputRange").setValue(20,1); + getField("OutputRange").setValue(20,2); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + CameraStabSettings obj = new CameraStabSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public CameraStabSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (CameraStabSettings)(objMngr.getObject(CameraStabSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x3B95DDBA; + protected static final String NAME = "CameraStabSettings"; + protected static String DESCRIPTION = "Settings for the @ref CameraStab mmodule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java similarity index 74% rename from androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java rename to androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java index 675f9b592..b22b8185e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemetrySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java @@ -5,7 +5,7 @@ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief Template for an uavobject in java * This is a autogenerated file!! Do not modify and expect a result. - * Select baud rate of telemetry. Warning - this must match your modem. + * Allows testers to simulate various fault scenarios. * * @see The GNU Public License (GPL) Version 3 * @@ -39,29 +39,28 @@ import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectField; /** -Select baud rate of telemetry. Warning - this must match your modem. +Allows testers to simulate various fault scenarios. -generated from telemetrysettings.xml +generated from faultsettings.xml **/ -public class TelemetrySettings extends UAVDataObject { +public class FaultSettings extends UAVDataObject { - public TelemetrySettings() { + public FaultSettings() { super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); List fields = new ArrayList(); - List SpeedElemNames = new ArrayList(); - SpeedElemNames.add("0"); - List SpeedEnumOptions = new ArrayList(); - SpeedEnumOptions.add("2400"); - SpeedEnumOptions.add("4800"); - SpeedEnumOptions.add("9600"); - SpeedEnumOptions.add("19200"); - SpeedEnumOptions.add("38400"); - SpeedEnumOptions.add("57600"); - SpeedEnumOptions.add("115200"); - fields.add( new UAVObjectField("Speed", "", UAVObjectField.FieldType.ENUM, SpeedElemNames, SpeedEnumOptions) ); + List ActivateFaultElemNames = new ArrayList(); + ActivateFaultElemNames.add("0"); + List ActivateFaultEnumOptions = new ArrayList(); + ActivateFaultEnumOptions.add("NoFault"); + ActivateFaultEnumOptions.add("ModuleInitAssert"); + ActivateFaultEnumOptions.add("InitOutOfMemory"); + ActivateFaultEnumOptions.add("InitBusError"); + ActivateFaultEnumOptions.add("RunawayTask"); + ActivateFaultEnumOptions.add("TaskOutOfMemory"); + fields.add( new UAVObjectField("ActivateFault", "fault", UAVObjectField.FieldType.ENUM, ActivateFaultElemNames, ActivateFaultEnumOptions) ); // Compute the number of bytes for this object @@ -108,7 +107,7 @@ public class TelemetrySettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Speed").setValue("57600"); + getField("ActivateFault").setValue("NoFault"); } @@ -120,7 +119,7 @@ public class TelemetrySettings extends UAVDataObject { public UAVDataObject clone(int instID) { // TODO: Need to get specific instance to clone try { - TelemetrySettings obj = new TelemetrySettings(); + FaultSettings obj = new FaultSettings(); obj.initialize(instID, this.getMetaObject()); return obj; } catch (Exception e) { @@ -131,15 +130,15 @@ public class TelemetrySettings extends UAVDataObject { /** * Static function to retrieve an instance of the object. */ - public TelemetrySettings GetInstance(UAVObjectManager objMngr, int instID) + public FaultSettings GetInstance(UAVObjectManager objMngr, int instID) { - return (TelemetrySettings)(objMngr.getObject(TelemetrySettings.OBJID, instID)); + return (FaultSettings)(objMngr.getObject(FaultSettings.OBJID, instID)); } // Constants - protected static final int OBJID = 0xA608C526; - protected static final String NAME = "TelemetrySettings"; - protected static String DESCRIPTION = "Select baud rate of telemetry. Warning - this must match your modem."; + protected static final int OBJID = 0x2778BA3C; + protected static final String NAME = "FaultSettings"; + protected static String DESCRIPTION = "Allows testers to simulate various fault scenarios."; protected static final boolean ISSINGLEINST = 1 == 1; protected static final boolean ISSETTINGS = 1 == 1; protected static int NUMBYTES = 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java index 493d6cd64..71c681bd2 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java @@ -5,7 +5,7 @@ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief Template for an uavobject in java * This is a autogenerated file!! Do not modify and expect a result. - * Firmware IAP + * Queries board for SN, model, revision, and sends reset command * * @see The GNU Public License (GPL) Version 3 * @@ -39,7 +39,7 @@ import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectField; /** -Firmware IAP +Queries board for SN, model, revision, and sends reset command generated from firmwareiapobj.xml **/ @@ -51,10 +51,18 @@ public class FirmwareIAPObj extends UAVDataObject { List fields = new ArrayList(); + List crcElemNames = new ArrayList(); + crcElemNames.add("0"); + fields.add( new UAVObjectField("crc", "", UAVObjectField.FieldType.UINT32, crcElemNames, null) ); + List CommandElemNames = new ArrayList(); CommandElemNames.add("0"); fields.add( new UAVObjectField("Command", "", UAVObjectField.FieldType.UINT16, CommandElemNames, null) ); + List BoardRevisionElemNames = new ArrayList(); + BoardRevisionElemNames.add("0"); + fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); + List DescriptionElemNames = new ArrayList(); DescriptionElemNames.add("0"); DescriptionElemNames.add("1"); @@ -96,71 +104,22 @@ public class FirmwareIAPObj extends UAVDataObject { DescriptionElemNames.add("37"); DescriptionElemNames.add("38"); DescriptionElemNames.add("39"); - DescriptionElemNames.add("40"); - DescriptionElemNames.add("41"); - DescriptionElemNames.add("42"); - DescriptionElemNames.add("43"); - DescriptionElemNames.add("44"); - DescriptionElemNames.add("45"); - DescriptionElemNames.add("46"); - DescriptionElemNames.add("47"); - DescriptionElemNames.add("48"); - DescriptionElemNames.add("49"); - DescriptionElemNames.add("50"); - DescriptionElemNames.add("51"); - DescriptionElemNames.add("52"); - DescriptionElemNames.add("53"); - DescriptionElemNames.add("54"); - DescriptionElemNames.add("55"); - DescriptionElemNames.add("56"); - DescriptionElemNames.add("57"); - DescriptionElemNames.add("58"); - DescriptionElemNames.add("59"); - DescriptionElemNames.add("60"); - DescriptionElemNames.add("61"); - DescriptionElemNames.add("62"); - DescriptionElemNames.add("63"); - DescriptionElemNames.add("64"); - DescriptionElemNames.add("65"); - DescriptionElemNames.add("66"); - DescriptionElemNames.add("67"); - DescriptionElemNames.add("68"); - DescriptionElemNames.add("69"); - DescriptionElemNames.add("70"); - DescriptionElemNames.add("71"); - DescriptionElemNames.add("72"); - DescriptionElemNames.add("73"); - DescriptionElemNames.add("74"); - DescriptionElemNames.add("75"); - DescriptionElemNames.add("76"); - DescriptionElemNames.add("77"); - DescriptionElemNames.add("78"); - DescriptionElemNames.add("79"); - DescriptionElemNames.add("80"); - DescriptionElemNames.add("81"); - DescriptionElemNames.add("82"); - DescriptionElemNames.add("83"); - DescriptionElemNames.add("84"); - DescriptionElemNames.add("85"); - DescriptionElemNames.add("86"); - DescriptionElemNames.add("87"); - DescriptionElemNames.add("88"); - DescriptionElemNames.add("89"); - DescriptionElemNames.add("90"); - DescriptionElemNames.add("91"); - DescriptionElemNames.add("92"); - DescriptionElemNames.add("93"); - DescriptionElemNames.add("94"); - DescriptionElemNames.add("95"); - DescriptionElemNames.add("96"); - DescriptionElemNames.add("97"); - DescriptionElemNames.add("98"); - DescriptionElemNames.add("99"); fields.add( new UAVObjectField("Description", "", UAVObjectField.FieldType.UINT8, DescriptionElemNames, null) ); - List BoardRevisionElemNames = new ArrayList(); - BoardRevisionElemNames.add("0"); - fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); + List CPUSerialElemNames = new ArrayList(); + CPUSerialElemNames.add("0"); + CPUSerialElemNames.add("1"); + CPUSerialElemNames.add("2"); + CPUSerialElemNames.add("3"); + CPUSerialElemNames.add("4"); + CPUSerialElemNames.add("5"); + CPUSerialElemNames.add("6"); + CPUSerialElemNames.add("7"); + CPUSerialElemNames.add("8"); + CPUSerialElemNames.add("9"); + CPUSerialElemNames.add("10"); + CPUSerialElemNames.add("11"); + fields.add( new UAVObjectField("CPUSerial", "", UAVObjectField.FieldType.UINT8, CPUSerialElemNames, null) ); List BoardTypeElemNames = new ArrayList(); BoardTypeElemNames.add("0"); @@ -170,10 +129,6 @@ public class FirmwareIAPObj extends UAVDataObject { ArmResetElemNames.add("0"); fields.add( new UAVObjectField("ArmReset", "", UAVObjectField.FieldType.UINT8, ArmResetElemNames, null) ); - List crcElemNames = new ArrayList(); - crcElemNames.add("0"); - fields.add( new UAVObjectField("crc", "", UAVObjectField.FieldType.UINT32, crcElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -247,9 +202,9 @@ public class FirmwareIAPObj extends UAVDataObject { } // Constants - protected static final int OBJID = 0x1A8ECC2; + protected static final int OBJID = 0x3CCDFB68; protected static final String NAME = "FirmwareIAPObj"; - protected static String DESCRIPTION = "Firmware IAP"; + protected static String DESCRIPTION = "Queries board for SN, model, revision, and sends reset command"; protected static final boolean ISSINGLEINST = 1 == 1; protected static final boolean ISSETTINGS = 0 == 1; protected static int NUMBYTES = 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java new file mode 100644 index 000000000..a3bc23eb3 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java @@ -0,0 +1,177 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Flight Battery configuration. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Flight Battery configuration. + +generated from flightbatterysettings.xml + **/ +public class FlightBatterySettings extends UAVDataObject { + + public FlightBatterySettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List CapacityElemNames = new ArrayList(); + CapacityElemNames.add("0"); + fields.add( new UAVObjectField("Capacity", "mAh", UAVObjectField.FieldType.UINT32, CapacityElemNames, null) ); + + List VoltageThresholdsElemNames = new ArrayList(); + VoltageThresholdsElemNames.add("Warning"); + VoltageThresholdsElemNames.add("Alarm"); + fields.add( new UAVObjectField("VoltageThresholds", "V", UAVObjectField.FieldType.FLOAT32, VoltageThresholdsElemNames, null) ); + + List SensorCalibrationsElemNames = new ArrayList(); + SensorCalibrationsElemNames.add("VoltageFactor"); + SensorCalibrationsElemNames.add("CurrentFactor"); + fields.add( new UAVObjectField("SensorCalibrations", "", UAVObjectField.FieldType.FLOAT32, SensorCalibrationsElemNames, null) ); + + List TypeElemNames = new ArrayList(); + TypeElemNames.add("0"); + List TypeEnumOptions = new ArrayList(); + TypeEnumOptions.add("LiPo"); + TypeEnumOptions.add("A123"); + TypeEnumOptions.add("LiCo"); + TypeEnumOptions.add("LiFeSO4"); + TypeEnumOptions.add("None"); + fields.add( new UAVObjectField("Type", "", UAVObjectField.FieldType.ENUM, TypeElemNames, TypeEnumOptions) ); + + List NbCellsElemNames = new ArrayList(); + NbCellsElemNames.add("0"); + fields.add( new UAVObjectField("NbCells", "", UAVObjectField.FieldType.UINT8, NbCellsElemNames, null) ); + + List SensorTypeElemNames = new ArrayList(); + SensorTypeElemNames.add("0"); + List SensorTypeEnumOptions = new ArrayList(); + SensorTypeEnumOptions.add("None"); + fields.add( new UAVObjectField("SensorType", "", UAVObjectField.FieldType.ENUM, SensorTypeElemNames, SensorTypeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Capacity").setValue(2200); + getField("VoltageThresholds").setValue(9.8,0); + getField("VoltageThresholds").setValue(9.2,1); + getField("SensorCalibrations").setValue(1,0); + getField("SensorCalibrations").setValue(1,1); + getField("Type").setValue("LiPo"); + getField("NbCells").setValue(3); + getField("SensorType").setValue("None"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightBatterySettings obj = new FlightBatterySettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightBatterySettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightBatterySettings)(objMngr.getObject(FlightBatterySettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xF172BB18; + protected static final String NAME = "FlightBatterySettings"; + protected static String DESCRIPTION = "Flight Battery configuration."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java index d9fba1de5..82fcfae47 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java @@ -154,7 +154,7 @@ public class FlightBatteryState extends UAVDataObject { } // Constants - protected static final int OBJID = 0x791A50E; + protected static final int OBJID = 0x8C0D756; protected static final String NAME = "FlightBatteryState"; protected static String DESCRIPTION = "Battery status information."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java index fdc5bfcb0..dbe959f96 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java @@ -133,7 +133,7 @@ public class FlightPlanControl extends UAVDataObject { } // Constants - protected static final int OBJID = 0x6B4FE6DA; + protected static final int OBJID = 0x53E3F180; protected static final String NAME = "FlightPlanControl"; protected static String DESCRIPTION = "Control the flight plan script"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java index 383e4aff0..6fc39a26e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java @@ -129,7 +129,7 @@ public class FlightPlanSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x85368422; + protected static final int OBJID = 0x92E9FF76; protected static final String NAME = "FlightPlanSettings"; protected static String DESCRIPTION = "Settings for the flight plan module, control the execution of the script"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java index 2303514c0..7b78bce71 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java @@ -51,6 +51,19 @@ public class FlightPlanStatus extends UAVDataObject { List fields = new ArrayList(); + List ErrorFileIDElemNames = new ArrayList(); + ErrorFileIDElemNames.add("0"); + fields.add( new UAVObjectField("ErrorFileID", "", UAVObjectField.FieldType.UINT32, ErrorFileIDElemNames, null) ); + + List ErrorLineNumElemNames = new ArrayList(); + ErrorLineNumElemNames.add("0"); + fields.add( new UAVObjectField("ErrorLineNum", "", UAVObjectField.FieldType.UINT32, ErrorLineNumElemNames, null) ); + + List DebugElemNames = new ArrayList(); + DebugElemNames.add("0"); + DebugElemNames.add("1"); + fields.add( new UAVObjectField("Debug", "", UAVObjectField.FieldType.FLOAT32, DebugElemNames, null) ); + List StatusElemNames = new ArrayList(); StatusElemNames.add("0"); List StatusEnumOptions = new ArrayList(); @@ -83,22 +96,6 @@ public class FlightPlanStatus extends UAVDataObject { ErrorTypeEnumOptions.add("UnknownError"); fields.add( new UAVObjectField("ErrorType", "", UAVObjectField.FieldType.ENUM, ErrorTypeElemNames, ErrorTypeEnumOptions) ); - List ErrorFileIDElemNames = new ArrayList(); - ErrorFileIDElemNames.add("0"); - fields.add( new UAVObjectField("ErrorFileID", "", UAVObjectField.FieldType.UINT32, ErrorFileIDElemNames, null) ); - - List ErrorLineNumElemNames = new ArrayList(); - ErrorLineNumElemNames.add("0"); - fields.add( new UAVObjectField("ErrorLineNum", "", UAVObjectField.FieldType.UINT32, ErrorLineNumElemNames, null) ); - - List Debug1ElemNames = new ArrayList(); - Debug1ElemNames.add("0"); - fields.add( new UAVObjectField("Debug1", "", UAVObjectField.FieldType.FLOAT32, Debug1ElemNames, null) ); - - List Debug2ElemNames = new ArrayList(); - Debug2ElemNames.add("0"); - fields.add( new UAVObjectField("Debug2", "", UAVObjectField.FieldType.FLOAT32, Debug2ElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -144,10 +141,10 @@ public class FlightPlanStatus extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("Debug").setValue(0,0); + getField("Debug").setValue(0,1); getField("Status").setValue("Stopped"); getField("ErrorType").setValue("None"); - getField("Debug1").setValue(0); - getField("Debug2").setValue(0); } @@ -176,7 +173,7 @@ public class FlightPlanStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x9FC14812; + protected static final int OBJID = 0x2206EE46; protected static final String NAME = "FlightPlanStatus"; protected static String DESCRIPTION = "Status of the flight plan script"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java new file mode 100644 index 000000000..d775b21e7 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java @@ -0,0 +1,155 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains major flight status information for other modules. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains major flight status information for other modules. + +generated from flightstatus.xml + **/ +public class FlightStatus extends UAVDataObject { + + public FlightStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ArmedElemNames = new ArrayList(); + ArmedElemNames.add("0"); + List ArmedEnumOptions = new ArrayList(); + ArmedEnumOptions.add("Disarmed"); + ArmedEnumOptions.add("Arming"); + ArmedEnumOptions.add("Armed"); + fields.add( new UAVObjectField("Armed", "", UAVObjectField.FieldType.ENUM, ArmedElemNames, ArmedEnumOptions) ); + + List FlightModeElemNames = new ArrayList(); + FlightModeElemNames.add("0"); + List FlightModeEnumOptions = new ArrayList(); + FlightModeEnumOptions.add("Manual"); + FlightModeEnumOptions.add("Stabilized1"); + FlightModeEnumOptions.add("Stabilized2"); + FlightModeEnumOptions.add("Stabilized3"); + FlightModeEnumOptions.add("VelocityControl"); + FlightModeEnumOptions.add("PositionHold"); + fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 5000; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Armed").setValue("Disarmed"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FlightStatus obj = new FlightStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FlightStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (FlightStatus)(objMngr.getObject(FlightStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x743DB13C; + protected static final String NAME = "FlightStatus"; + protected static String DESCRIPTION = "Contains major flight status information for other modules."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java index b58fe6d46..403ea1d5e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java @@ -51,15 +51,6 @@ public class FlightTelemetryStats extends UAVDataObject { List fields = new ArrayList(); - List StatusElemNames = new ArrayList(); - StatusElemNames.add("0"); - List StatusEnumOptions = new ArrayList(); - StatusEnumOptions.add("Disconnected"); - StatusEnumOptions.add("HandshakeReq"); - StatusEnumOptions.add("HandshakeAck"); - StatusEnumOptions.add("Connected"); - fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); - List TxDataRateElemNames = new ArrayList(); TxDataRateElemNames.add("0"); fields.add( new UAVObjectField("TxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, TxDataRateElemNames, null) ); @@ -80,6 +71,15 @@ public class FlightTelemetryStats extends UAVDataObject { TxRetriesElemNames.add("0"); fields.add( new UAVObjectField("TxRetries", "count", UAVObjectField.FieldType.UINT32, TxRetriesElemNames, null) ); + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Disconnected"); + StatusEnumOptions.add("HandshakeReq"); + StatusEnumOptions.add("HandshakeAck"); + StatusEnumOptions.add("Connected"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -153,7 +153,7 @@ public class FlightTelemetryStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0x660C265E; + protected static final int OBJID = 0x2F7E2902; protected static final String NAME = "FlightTelemetryStats"; protected static String DESCRIPTION = "Maintains the telemetry statistics from the OpenPilot flight computer."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java new file mode 100644 index 000000000..3cb3811ae --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java @@ -0,0 +1,144 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * A receiver channel group carried over the telemetry link. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +A receiver channel group carried over the telemetry link. + +generated from gcsreceiver.xml + **/ +public class GCSReceiver extends UAVDataObject { + + public GCSReceiver() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ChannelElemNames = new ArrayList(); + ChannelElemNames.add("0"); + ChannelElemNames.add("1"); + ChannelElemNames.add("2"); + ChannelElemNames.add("3"); + ChannelElemNames.add("4"); + ChannelElemNames.add("5"); + fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READONLY; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GCSReceiver obj = new GCSReceiver(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GCSReceiver GetInstance(UAVObjectManager objMngr, int instID) + { + return (GCSReceiver)(objMngr.getObject(GCSReceiver.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xCC7E2BBC; + protected static final String NAME = "GCSReceiver"; + protected static String DESCRIPTION = "A receiver channel group carried over the telemetry link."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java index 0f304d45d..b32f551ce 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java @@ -51,15 +51,6 @@ public class GCSTelemetryStats extends UAVDataObject { List fields = new ArrayList(); - List StatusElemNames = new ArrayList(); - StatusElemNames.add("0"); - List StatusEnumOptions = new ArrayList(); - StatusEnumOptions.add("Disconnected"); - StatusEnumOptions.add("HandshakeReq"); - StatusEnumOptions.add("HandshakeAck"); - StatusEnumOptions.add("Connected"); - fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); - List TxDataRateElemNames = new ArrayList(); TxDataRateElemNames.add("0"); fields.add( new UAVObjectField("TxDataRate", "bytes/sec", UAVObjectField.FieldType.FLOAT32, TxDataRateElemNames, null) ); @@ -80,6 +71,15 @@ public class GCSTelemetryStats extends UAVDataObject { TxRetriesElemNames.add("0"); fields.add( new UAVObjectField("TxRetries", "count", UAVObjectField.FieldType.UINT32, TxRetriesElemNames, null) ); + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("Disconnected"); + StatusEnumOptions.add("HandshakeReq"); + StatusEnumOptions.add("HandshakeAck"); + StatusEnumOptions.add("Connected"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -153,7 +153,7 @@ public class GCSTelemetryStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0x771E1046; + protected static final int OBJID = 0xABC72744; protected static final String NAME = "GCSTelemetryStats"; protected static String DESCRIPTION = "The telemetry statistics from the ground computer"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java index 889091e0e..5f4e20b46 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java @@ -51,15 +51,6 @@ public class GPSPosition extends UAVDataObject { List fields = new ArrayList(); - List StatusElemNames = new ArrayList(); - StatusElemNames.add("0"); - List StatusEnumOptions = new ArrayList(); - StatusEnumOptions.add("NoGPS"); - StatusEnumOptions.add("NoFix"); - StatusEnumOptions.add("Fix2D"); - StatusEnumOptions.add("Fix3D"); - fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); - List LatitudeElemNames = new ArrayList(); LatitudeElemNames.add("0"); fields.add( new UAVObjectField("Latitude", "degrees x 10^-7", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); @@ -84,10 +75,6 @@ public class GPSPosition extends UAVDataObject { GroundspeedElemNames.add("0"); fields.add( new UAVObjectField("Groundspeed", "m/s", UAVObjectField.FieldType.FLOAT32, GroundspeedElemNames, null) ); - List SatellitesElemNames = new ArrayList(); - SatellitesElemNames.add("0"); - fields.add( new UAVObjectField("Satellites", "", UAVObjectField.FieldType.INT8, SatellitesElemNames, null) ); - List PDOPElemNames = new ArrayList(); PDOPElemNames.add("0"); fields.add( new UAVObjectField("PDOP", "", UAVObjectField.FieldType.FLOAT32, PDOPElemNames, null) ); @@ -100,6 +87,19 @@ public class GPSPosition extends UAVDataObject { VDOPElemNames.add("0"); fields.add( new UAVObjectField("VDOP", "", UAVObjectField.FieldType.FLOAT32, VDOPElemNames, null) ); + List StatusElemNames = new ArrayList(); + StatusElemNames.add("0"); + List StatusEnumOptions = new ArrayList(); + StatusEnumOptions.add("NoGPS"); + StatusEnumOptions.add("NoFix"); + StatusEnumOptions.add("Fix2D"); + StatusEnumOptions.add("Fix3D"); + fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); + + List SatellitesElemNames = new ArrayList(); + SatellitesElemNames.add("0"); + fields.add( new UAVObjectField("Satellites", "", UAVObjectField.FieldType.INT8, SatellitesElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -173,7 +173,7 @@ public class GPSPosition extends UAVDataObject { } // Constants - protected static final int OBJID = 0xB5495042; + protected static final int OBJID = 0xE2A323B6; protected static final String NAME = "GPSPosition"; protected static String DESCRIPTION = "Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java index fa1100207..bb331132d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java @@ -51,29 +51,6 @@ public class GPSSatellites extends UAVDataObject { List fields = new ArrayList(); - List SatsInViewElemNames = new ArrayList(); - SatsInViewElemNames.add("0"); - fields.add( new UAVObjectField("SatsInView", "", UAVObjectField.FieldType.INT8, SatsInViewElemNames, null) ); - - List PRNElemNames = new ArrayList(); - PRNElemNames.add("0"); - PRNElemNames.add("1"); - PRNElemNames.add("2"); - PRNElemNames.add("3"); - PRNElemNames.add("4"); - PRNElemNames.add("5"); - PRNElemNames.add("6"); - PRNElemNames.add("7"); - PRNElemNames.add("8"); - PRNElemNames.add("9"); - PRNElemNames.add("10"); - PRNElemNames.add("11"); - PRNElemNames.add("12"); - PRNElemNames.add("13"); - PRNElemNames.add("14"); - PRNElemNames.add("15"); - fields.add( new UAVObjectField("PRN", "", UAVObjectField.FieldType.INT8, PRNElemNames, null) ); - List ElevationElemNames = new ArrayList(); ElevationElemNames.add("0"); ElevationElemNames.add("1"); @@ -112,6 +89,29 @@ public class GPSSatellites extends UAVDataObject { AzimuthElemNames.add("15"); fields.add( new UAVObjectField("Azimuth", "degrees", UAVObjectField.FieldType.FLOAT32, AzimuthElemNames, null) ); + List SatsInViewElemNames = new ArrayList(); + SatsInViewElemNames.add("0"); + fields.add( new UAVObjectField("SatsInView", "", UAVObjectField.FieldType.INT8, SatsInViewElemNames, null) ); + + List PRNElemNames = new ArrayList(); + PRNElemNames.add("0"); + PRNElemNames.add("1"); + PRNElemNames.add("2"); + PRNElemNames.add("3"); + PRNElemNames.add("4"); + PRNElemNames.add("5"); + PRNElemNames.add("6"); + PRNElemNames.add("7"); + PRNElemNames.add("8"); + PRNElemNames.add("9"); + PRNElemNames.add("10"); + PRNElemNames.add("11"); + PRNElemNames.add("12"); + PRNElemNames.add("13"); + PRNElemNames.add("14"); + PRNElemNames.add("15"); + fields.add( new UAVObjectField("PRN", "", UAVObjectField.FieldType.INT8, PRNElemNames, null) ); + List SNRElemNames = new ArrayList(); SNRElemNames.add("0"); SNRElemNames.add("1"); @@ -204,7 +204,7 @@ public class GPSSatellites extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD62FA3AE; + protected static final int OBJID = 0x920D998; protected static final String NAME = "GPSSatellites"; protected static String DESCRIPTION = "Contains information about the GPS satellites in view from @ref GPSModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java index 5ff55cc2e..5aa4df7bf 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java @@ -51,6 +51,10 @@ public class GPSTime extends UAVDataObject { List fields = new ArrayList(); + List YearElemNames = new ArrayList(); + YearElemNames.add("0"); + fields.add( new UAVObjectField("Year", "", UAVObjectField.FieldType.INT16, YearElemNames, null) ); + List MonthElemNames = new ArrayList(); MonthElemNames.add("0"); fields.add( new UAVObjectField("Month", "", UAVObjectField.FieldType.INT8, MonthElemNames, null) ); @@ -59,10 +63,6 @@ public class GPSTime extends UAVDataObject { DayElemNames.add("0"); fields.add( new UAVObjectField("Day", "", UAVObjectField.FieldType.INT8, DayElemNames, null) ); - List YearElemNames = new ArrayList(); - YearElemNames.add("0"); - fields.add( new UAVObjectField("Year", "", UAVObjectField.FieldType.INT16, YearElemNames, null) ); - List HourElemNames = new ArrayList(); HourElemNames.add("0"); fields.add( new UAVObjectField("Hour", "", UAVObjectField.FieldType.INT8, HourElemNames, null) ); @@ -148,7 +148,7 @@ public class GPSTime extends UAVDataObject { } // Constants - protected static final int OBJID = 0x56FFF0A2; + protected static final int OBJID = 0xD4478084; protected static final String NAME = "GPSTime"; protected static String DESCRIPTION = "Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java index 2fe8bb437..205384efe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java @@ -51,29 +51,24 @@ public class GuidanceSettings extends UAVDataObject { List fields = new ArrayList(); - List GuidanceModeElemNames = new ArrayList(); - GuidanceModeElemNames.add("0"); - List GuidanceModeEnumOptions = new ArrayList(); - GuidanceModeEnumOptions.add("DUAL_LOOP"); - GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); - fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); - - List HorizontalPElemNames = new ArrayList(); - HorizontalPElemNames.add("Kp"); - HorizontalPElemNames.add("Max"); - fields.add( new UAVObjectField("HorizontalP", "", UAVObjectField.FieldType.FLOAT32, HorizontalPElemNames, null) ); + List HorizontalPosPIElemNames = new ArrayList(); + HorizontalPosPIElemNames.add("Kp"); + HorizontalPosPIElemNames.add("Ki"); + HorizontalPosPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("HorizontalPosPI", "(cm/s)/cm", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); List HorizontalVelPIDElemNames = new ArrayList(); HorizontalVelPIDElemNames.add("Kp"); HorizontalVelPIDElemNames.add("Ki"); HorizontalVelPIDElemNames.add("Kd"); HorizontalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalVelPID", "", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); + fields.add( new UAVObjectField("HorizontalVelPID", "deg/(cm/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); - List VerticalPElemNames = new ArrayList(); - VerticalPElemNames.add("Kp"); - VerticalPElemNames.add("Max"); - fields.add( new UAVObjectField("VerticalP", "", UAVObjectField.FieldType.FLOAT32, VerticalPElemNames, null) ); + List VerticalPosPIElemNames = new ArrayList(); + VerticalPosPIElemNames.add("Kp"); + VerticalPosPIElemNames.add("Ki"); + VerticalPosPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("VerticalPosPI", "", UAVObjectField.FieldType.FLOAT32, VerticalPosPIElemNames, null) ); List VerticalVelPIDElemNames = new ArrayList(); VerticalVelPIDElemNames.add("Kp"); @@ -82,13 +77,6 @@ public class GuidanceSettings extends UAVDataObject { VerticalVelPIDElemNames.add("ILimit"); fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); - List ThrottleControlElemNames = new ArrayList(); - ThrottleControlElemNames.add("0"); - List ThrottleControlEnumOptions = new ArrayList(); - ThrottleControlEnumOptions.add("FALSE"); - ThrottleControlEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); - List MaxRollPitchElemNames = new ArrayList(); MaxRollPitchElemNames.add("0"); fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); @@ -97,6 +85,28 @@ public class GuidanceSettings extends UAVDataObject { UpdatePeriodElemNames.add("0"); fields.add( new UAVObjectField("UpdatePeriod", "", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); + List HorizontalVelMaxElemNames = new ArrayList(); + HorizontalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("HorizontalVelMax", "cm/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); + + List VerticalVelMaxElemNames = new ArrayList(); + VerticalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("VerticalVelMax", "cm/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); + + List GuidanceModeElemNames = new ArrayList(); + GuidanceModeElemNames.add("0"); + List GuidanceModeEnumOptions = new ArrayList(); + GuidanceModeEnumOptions.add("DUAL_LOOP"); + GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); + fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); + + List ThrottleControlElemNames = new ArrayList(); + ThrottleControlElemNames.add("0"); + List ThrottleControlEnumOptions = new ArrayList(); + ThrottleControlEnumOptions.add("FALSE"); + ThrottleControlEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -142,22 +152,26 @@ public class GuidanceSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("GuidanceMode").setValue("DUAL_LOOP"); - getField("HorizontalP").setValue(0.2,0); - getField("HorizontalP").setValue(150,1); - getField("HorizontalVelPID").setValue(0.1,0); + getField("HorizontalPosPI").setValue(0.1,0); + getField("HorizontalPosPI").setValue(0.001,1); + getField("HorizontalPosPI").setValue(300,2); + getField("HorizontalVelPID").setValue(0.05,0); getField("HorizontalVelPID").setValue(0.002,1); getField("HorizontalVelPID").setValue(0,2); getField("HorizontalVelPID").setValue(1000,3); - getField("VerticalP").setValue(0.1,0); - getField("VerticalP").setValue(200,1); + getField("VerticalPosPI").setValue(0.1,0); + getField("VerticalPosPI").setValue(0.001,1); + getField("VerticalPosPI").setValue(200,2); getField("VerticalVelPID").setValue(0.1,0); getField("VerticalVelPID").setValue(0,1); getField("VerticalVelPID").setValue(0,2); getField("VerticalVelPID").setValue(0,3); - getField("ThrottleControl").setValue("FALSE"); getField("MaxRollPitch").setValue(10); getField("UpdatePeriod").setValue(100); + getField("HorizontalVelMax").setValue(300); + getField("VerticalVelMax").setValue(150); + getField("GuidanceMode").setValue("DUAL_LOOP"); + getField("ThrottleControl").setValue("FALSE"); } @@ -186,7 +200,7 @@ public class GuidanceSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x74740AA2; + protected static final int OBJID = 0x6EA79FB4; protected static final String NAME = "GuidanceSettings"; protected static String DESCRIPTION = "Settings for the @ref GuidanceModule"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java index 5941c069c..68abb3633 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -51,13 +51,6 @@ public class HomeLocation extends UAVDataObject { List fields = new ArrayList(); - List SetElemNames = new ArrayList(); - SetElemNames.add("0"); - List SetEnumOptions = new ArrayList(); - SetEnumOptions.add("FALSE"); - SetEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("Set", "", UAVObjectField.FieldType.ENUM, SetElemNames, SetEnumOptions) ); - List LatitudeElemNames = new ArrayList(); LatitudeElemNames.add("0"); fields.add( new UAVObjectField("Latitude", "deg * 10e6", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); @@ -94,6 +87,17 @@ public class HomeLocation extends UAVDataObject { BeElemNames.add("2"); fields.add( new UAVObjectField("Be", "", UAVObjectField.FieldType.FLOAT32, BeElemNames, null) ); + List g_eElemNames = new ArrayList(); + g_eElemNames.add("0"); + fields.add( new UAVObjectField("g_e", "m/s^2", UAVObjectField.FieldType.FLOAT32, g_eElemNames, null) ); + + List SetElemNames = new ArrayList(); + SetElemNames.add("0"); + List SetEnumOptions = new ArrayList(); + SetEnumOptions.add("FALSE"); + SetEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("Set", "", UAVObjectField.FieldType.ENUM, SetElemNames, SetEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -139,7 +143,6 @@ public class HomeLocation extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("Set").setValue("FALSE"); getField("Latitude").setValue(0); getField("Longitude").setValue(0); getField("Altitude").setValue(0); @@ -158,6 +161,8 @@ public class HomeLocation extends UAVDataObject { getField("Be").setValue(0,0); getField("Be").setValue(0,1); getField("Be").setValue(0,2); + getField("g_e").setValue(9.81); + getField("Set").setValue("FALSE"); } @@ -186,7 +191,7 @@ public class HomeLocation extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD6008ED2; + protected static final int OBJID = 0x5BB3AEFC; protected static final String NAME = "HomeLocation"; protected static String DESCRIPTION = "HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java new file mode 100644 index 000000000..83b7ae7b6 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java @@ -0,0 +1,291 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Selection of optional hardware configurations. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Selection of optional hardware configurations. + +generated from hwsettings.xml + **/ +public class HwSettings extends UAVDataObject { + + public HwSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List CC_RcvrPortElemNames = new ArrayList(); + CC_RcvrPortElemNames.add("0"); + List CC_RcvrPortEnumOptions = new ArrayList(); + CC_RcvrPortEnumOptions.add("Disabled"); + CC_RcvrPortEnumOptions.add("PWM"); + CC_RcvrPortEnumOptions.add("PPM"); + CC_RcvrPortEnumOptions.add("PPM+Outputs"); + CC_RcvrPortEnumOptions.add("Outputs"); + fields.add( new UAVObjectField("CC_RcvrPort", "function", UAVObjectField.FieldType.ENUM, CC_RcvrPortElemNames, CC_RcvrPortEnumOptions) ); + + List CC_MainPortElemNames = new ArrayList(); + CC_MainPortElemNames.add("0"); + List CC_MainPortEnumOptions = new ArrayList(); + CC_MainPortEnumOptions.add("Disabled"); + CC_MainPortEnumOptions.add("Telemetry"); + CC_MainPortEnumOptions.add("GPS"); + CC_MainPortEnumOptions.add("S.Bus"); + CC_MainPortEnumOptions.add("DSM2"); + CC_MainPortEnumOptions.add("DSMX (10bit)"); + CC_MainPortEnumOptions.add("DSMX (11bit)"); + CC_MainPortEnumOptions.add("ComAux"); + CC_MainPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("CC_MainPort", "function", UAVObjectField.FieldType.ENUM, CC_MainPortElemNames, CC_MainPortEnumOptions) ); + + List CC_FlexiPortElemNames = new ArrayList(); + CC_FlexiPortElemNames.add("0"); + List CC_FlexiPortEnumOptions = new ArrayList(); + CC_FlexiPortEnumOptions.add("Disabled"); + CC_FlexiPortEnumOptions.add("Telemetry"); + CC_FlexiPortEnumOptions.add("GPS"); + CC_FlexiPortEnumOptions.add("I2C"); + CC_FlexiPortEnumOptions.add("DSM2"); + CC_FlexiPortEnumOptions.add("DSMX (10bit)"); + CC_FlexiPortEnumOptions.add("DSMX (11bit)"); + CC_FlexiPortEnumOptions.add("ComAux"); + CC_FlexiPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("CC_FlexiPort", "function", UAVObjectField.FieldType.ENUM, CC_FlexiPortElemNames, CC_FlexiPortEnumOptions) ); + + List OP_RcvrPortElemNames = new ArrayList(); + OP_RcvrPortElemNames.add("0"); + List OP_RcvrPortEnumOptions = new ArrayList(); + OP_RcvrPortEnumOptions.add("Disabled"); + OP_RcvrPortEnumOptions.add("PWM"); + OP_RcvrPortEnumOptions.add("PPM"); + OP_RcvrPortEnumOptions.add("DSM2"); + OP_RcvrPortEnumOptions.add("DSMX (10bit)"); + OP_RcvrPortEnumOptions.add("DSMX (11bit)"); + OP_RcvrPortEnumOptions.add("Debug"); + fields.add( new UAVObjectField("OP_RcvrPort", "function", UAVObjectField.FieldType.ENUM, OP_RcvrPortElemNames, OP_RcvrPortEnumOptions) ); + + List OP_MainPortElemNames = new ArrayList(); + OP_MainPortElemNames.add("0"); + List OP_MainPortEnumOptions = new ArrayList(); + OP_MainPortEnumOptions.add("Disabled"); + OP_MainPortEnumOptions.add("Telemetry"); + fields.add( new UAVObjectField("OP_MainPort", "function", UAVObjectField.FieldType.ENUM, OP_MainPortElemNames, OP_MainPortEnumOptions) ); + + List OP_FlexiPortElemNames = new ArrayList(); + OP_FlexiPortElemNames.add("0"); + List OP_FlexiPortEnumOptions = new ArrayList(); + OP_FlexiPortEnumOptions.add("Disabled"); + OP_FlexiPortEnumOptions.add("GPS"); + fields.add( new UAVObjectField("OP_FlexiPort", "function", UAVObjectField.FieldType.ENUM, OP_FlexiPortElemNames, OP_FlexiPortEnumOptions) ); + + List TelemetrySpeedElemNames = new ArrayList(); + TelemetrySpeedElemNames.add("0"); + List TelemetrySpeedEnumOptions = new ArrayList(); + TelemetrySpeedEnumOptions.add("2400"); + TelemetrySpeedEnumOptions.add("4800"); + TelemetrySpeedEnumOptions.add("9600"); + TelemetrySpeedEnumOptions.add("19200"); + TelemetrySpeedEnumOptions.add("38400"); + TelemetrySpeedEnumOptions.add("57600"); + TelemetrySpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("TelemetrySpeed", "bps", UAVObjectField.FieldType.ENUM, TelemetrySpeedElemNames, TelemetrySpeedEnumOptions) ); + + List GPSSpeedElemNames = new ArrayList(); + GPSSpeedElemNames.add("0"); + List GPSSpeedEnumOptions = new ArrayList(); + GPSSpeedEnumOptions.add("2400"); + GPSSpeedEnumOptions.add("4800"); + GPSSpeedEnumOptions.add("9600"); + GPSSpeedEnumOptions.add("19200"); + GPSSpeedEnumOptions.add("38400"); + GPSSpeedEnumOptions.add("57600"); + GPSSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("GPSSpeed", "bps", UAVObjectField.FieldType.ENUM, GPSSpeedElemNames, GPSSpeedEnumOptions) ); + + List ComUsbBridgeSpeedElemNames = new ArrayList(); + ComUsbBridgeSpeedElemNames.add("0"); + List ComUsbBridgeSpeedEnumOptions = new ArrayList(); + ComUsbBridgeSpeedEnumOptions.add("2400"); + ComUsbBridgeSpeedEnumOptions.add("4800"); + ComUsbBridgeSpeedEnumOptions.add("9600"); + ComUsbBridgeSpeedEnumOptions.add("19200"); + ComUsbBridgeSpeedEnumOptions.add("38400"); + ComUsbBridgeSpeedEnumOptions.add("57600"); + ComUsbBridgeSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("ComUsbBridgeSpeed", "bps", UAVObjectField.FieldType.ENUM, ComUsbBridgeSpeedElemNames, ComUsbBridgeSpeedEnumOptions) ); + + List USB_DeviceTypeElemNames = new ArrayList(); + USB_DeviceTypeElemNames.add("0"); + List USB_DeviceTypeEnumOptions = new ArrayList(); + USB_DeviceTypeEnumOptions.add("HID-only"); + USB_DeviceTypeEnumOptions.add("HID+VCP"); + USB_DeviceTypeEnumOptions.add("VCP-only"); + fields.add( new UAVObjectField("USB_DeviceType", "descriptor", UAVObjectField.FieldType.ENUM, USB_DeviceTypeElemNames, USB_DeviceTypeEnumOptions) ); + + List USB_HIDPortElemNames = new ArrayList(); + USB_HIDPortElemNames.add("0"); + List USB_HIDPortEnumOptions = new ArrayList(); + USB_HIDPortEnumOptions.add("USBTelemetry"); + USB_HIDPortEnumOptions.add("Disabled"); + fields.add( new UAVObjectField("USB_HIDPort", "function", UAVObjectField.FieldType.ENUM, USB_HIDPortElemNames, USB_HIDPortEnumOptions) ); + + List USB_VCPPortElemNames = new ArrayList(); + USB_VCPPortElemNames.add("0"); + List USB_VCPPortEnumOptions = new ArrayList(); + USB_VCPPortEnumOptions.add("USBTelemetry"); + USB_VCPPortEnumOptions.add("ComBridge"); + USB_VCPPortEnumOptions.add("Disabled"); + fields.add( new UAVObjectField("USB_VCPPort", "function", UAVObjectField.FieldType.ENUM, USB_VCPPortElemNames, USB_VCPPortEnumOptions) ); + + List OptionalModulesElemNames = new ArrayList(); + OptionalModulesElemNames.add("CameraStab"); + OptionalModulesElemNames.add("GPS"); + OptionalModulesElemNames.add("ComUsbBridge"); + OptionalModulesElemNames.add("Fault"); + OptionalModulesElemNames.add("Altitude"); + List OptionalModulesEnumOptions = new ArrayList(); + OptionalModulesEnumOptions.add("Disabled"); + OptionalModulesEnumOptions.add("Enabled"); + fields.add( new UAVObjectField("OptionalModules", "", UAVObjectField.FieldType.ENUM, OptionalModulesElemNames, OptionalModulesEnumOptions) ); + + List DSMxBindElemNames = new ArrayList(); + DSMxBindElemNames.add("0"); + fields.add( new UAVObjectField("DSMxBind", "", UAVObjectField.FieldType.UINT8, DSMxBindElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsTelemetryUpdatePeriod = 0; + + metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; + metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; + + metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; + metadata.loggingUpdatePeriod = 0; + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("CC_RcvrPort").setValue("PWM"); + getField("CC_MainPort").setValue("Disabled"); + getField("CC_FlexiPort").setValue("Disabled"); + getField("OP_RcvrPort").setValue("PWM"); + getField("OP_MainPort").setValue("Telemetry"); + getField("OP_FlexiPort").setValue("GPS"); + getField("TelemetrySpeed").setValue("57600"); + getField("GPSSpeed").setValue("57600"); + getField("ComUsbBridgeSpeed").setValue("57600"); + getField("USB_DeviceType").setValue("HID-only"); + getField("USB_HIDPort").setValue("USBTelemetry"); + getField("USB_VCPPort").setValue("Disabled"); + getField("OptionalModules").setValue("Disabled",0); + getField("OptionalModules").setValue("Disabled",1); + getField("OptionalModules").setValue("Disabled",2); + getField("OptionalModules").setValue("Disabled",3); + getField("OptionalModules").setValue("Disabled",4); + getField("DSMxBind").setValue(0); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + HwSettings obj = new HwSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public HwSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (HwSettings)(objMngr.getObject(HwSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x2EE6575A; + protected static final String NAME = "HwSettings"; + protected static String DESCRIPTION = "Selection of optional hardware configurations."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java index fc68e2902..abd8f41f6 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java @@ -51,6 +51,22 @@ public class I2CStats extends UAVDataObject { List fields = new ArrayList(); + List evirq_logElemNames = new ArrayList(); + evirq_logElemNames.add("0"); + evirq_logElemNames.add("1"); + evirq_logElemNames.add("2"); + evirq_logElemNames.add("3"); + evirq_logElemNames.add("4"); + fields.add( new UAVObjectField("evirq_log", "", UAVObjectField.FieldType.UINT32, evirq_logElemNames, null) ); + + List erirq_logElemNames = new ArrayList(); + erirq_logElemNames.add("0"); + erirq_logElemNames.add("1"); + erirq_logElemNames.add("2"); + erirq_logElemNames.add("3"); + erirq_logElemNames.add("4"); + fields.add( new UAVObjectField("erirq_log", "", UAVObjectField.FieldType.UINT32, erirq_logElemNames, null) ); + List event_errorsElemNames = new ArrayList(); event_errorsElemNames.add("0"); fields.add( new UAVObjectField("event_errors", "", UAVObjectField.FieldType.UINT8, event_errorsElemNames, null) ); @@ -79,22 +95,6 @@ public class I2CStats extends UAVDataObject { last_error_typeEnumOptions.add("INTERRUPT"); fields.add( new UAVObjectField("last_error_type", "", UAVObjectField.FieldType.ENUM, last_error_typeElemNames, last_error_typeEnumOptions) ); - List evirq_logElemNames = new ArrayList(); - evirq_logElemNames.add("0"); - evirq_logElemNames.add("1"); - evirq_logElemNames.add("2"); - evirq_logElemNames.add("3"); - evirq_logElemNames.add("4"); - fields.add( new UAVObjectField("evirq_log", "", UAVObjectField.FieldType.UINT32, evirq_logElemNames, null) ); - - List erirq_logElemNames = new ArrayList(); - erirq_logElemNames.add("0"); - erirq_logElemNames.add("1"); - erirq_logElemNames.add("2"); - erirq_logElemNames.add("3"); - erirq_logElemNames.add("4"); - fields.add( new UAVObjectField("erirq_log", "", UAVObjectField.FieldType.UINT32, erirq_logElemNames, null) ); - List event_logElemNames = new ArrayList(); event_logElemNames.add("0"); event_logElemNames.add("1"); @@ -227,7 +227,7 @@ public class I2CStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0x23CE9E9C; + protected static final int OBJID = 0xB714823E; protected static final String NAME = "I2CStats"; protected static String DESCRIPTION = "Tracks statistics on the I2C bus."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java index 636f30946..6ac5a1b2c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java @@ -51,19 +51,9 @@ public class ManualControlCommand extends UAVDataObject { List fields = new ArrayList(); - List ConnectedElemNames = new ArrayList(); - ConnectedElemNames.add("0"); - List ConnectedEnumOptions = new ArrayList(); - ConnectedEnumOptions.add("False"); - ConnectedEnumOptions.add("True"); - fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); - - List ArmedElemNames = new ArrayList(); - ArmedElemNames.add("0"); - List ArmedEnumOptions = new ArrayList(); - ArmedEnumOptions.add("False"); - ArmedEnumOptions.add("True"); - fields.add( new UAVObjectField("Armed", "", UAVObjectField.FieldType.ENUM, ArmedElemNames, ArmedEnumOptions) ); + List ThrottleElemNames = new ArrayList(); + ThrottleElemNames.add("0"); + fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); List RollElemNames = new ArrayList(); RollElemNames.add("0"); @@ -77,32 +67,9 @@ public class ManualControlCommand extends UAVDataObject { YawElemNames.add("0"); fields.add( new UAVObjectField("Yaw", "%", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); - List ThrottleElemNames = new ArrayList(); - ThrottleElemNames.add("0"); - fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); - - List FlightModeElemNames = new ArrayList(); - FlightModeElemNames.add("0"); - List FlightModeEnumOptions = new ArrayList(); - FlightModeEnumOptions.add("Manual"); - FlightModeEnumOptions.add("Stabilized1"); - FlightModeEnumOptions.add("Stabilized2"); - FlightModeEnumOptions.add("Stabilized3"); - FlightModeEnumOptions.add("VelocityControl"); - FlightModeEnumOptions.add("PositionHold"); - fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); - - List Accessory1ElemNames = new ArrayList(); - Accessory1ElemNames.add("0"); - fields.add( new UAVObjectField("Accessory1", "%", UAVObjectField.FieldType.FLOAT32, Accessory1ElemNames, null) ); - - List Accessory2ElemNames = new ArrayList(); - Accessory2ElemNames.add("0"); - fields.add( new UAVObjectField("Accessory2", "%", UAVObjectField.FieldType.FLOAT32, Accessory2ElemNames, null) ); - - List Accessory3ElemNames = new ArrayList(); - Accessory3ElemNames.add("0"); - fields.add( new UAVObjectField("Accessory3", "%", UAVObjectField.FieldType.FLOAT32, Accessory3ElemNames, null) ); + List CollectiveElemNames = new ArrayList(); + CollectiveElemNames.add("0"); + fields.add( new UAVObjectField("Collective", "%", UAVObjectField.FieldType.FLOAT32, CollectiveElemNames, null) ); List ChannelElemNames = new ArrayList(); ChannelElemNames.add("0"); @@ -113,8 +80,16 @@ public class ManualControlCommand extends UAVDataObject { ChannelElemNames.add("5"); ChannelElemNames.add("6"); ChannelElemNames.add("7"); + ChannelElemNames.add("8"); fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); + List ConnectedElemNames = new ArrayList(); + ConnectedElemNames.add("0"); + List ConnectedEnumOptions = new ArrayList(); + ConnectedEnumOptions.add("False"); + ConnectedEnumOptions.add("True"); + fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -188,7 +163,7 @@ public class ManualControlCommand extends UAVDataObject { } // Constants - protected static final int OBJID = 0x926794; + protected static final int OBJID = 0x1E82C2D2; protected static final String NAME = "ManualControlCommand"; protected static String DESCRIPTION = "The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java index 83697999a..bb846695d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -51,125 +51,77 @@ public class ManualControlSettings extends UAVDataObject { List fields = new ArrayList(); - List InputModeElemNames = new ArrayList(); - InputModeElemNames.add("0"); - List InputModeEnumOptions = new ArrayList(); - InputModeEnumOptions.add("PWM"); - InputModeEnumOptions.add("PPM"); - InputModeEnumOptions.add("Spektrum"); - fields.add( new UAVObjectField("InputMode", "", UAVObjectField.FieldType.ENUM, InputModeElemNames, InputModeEnumOptions) ); + List ChannelMinElemNames = new ArrayList(); + ChannelMinElemNames.add("Throttle"); + ChannelMinElemNames.add("Roll"); + ChannelMinElemNames.add("Pitch"); + ChannelMinElemNames.add("Yaw"); + ChannelMinElemNames.add("FlightMode"); + ChannelMinElemNames.add("Collective"); + ChannelMinElemNames.add("Accessory0"); + ChannelMinElemNames.add("Accessory1"); + ChannelMinElemNames.add("Accessory2"); + fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); - List RollElemNames = new ArrayList(); - RollElemNames.add("0"); - List RollEnumOptions = new ArrayList(); - RollEnumOptions.add("Channel1"); - RollEnumOptions.add("Channel2"); - RollEnumOptions.add("Channel3"); - RollEnumOptions.add("Channel4"); - RollEnumOptions.add("Channel5"); - RollEnumOptions.add("Channel6"); - RollEnumOptions.add("Channel7"); - RollEnumOptions.add("Channel8"); - RollEnumOptions.add("None"); - fields.add( new UAVObjectField("Roll", "channel", UAVObjectField.FieldType.ENUM, RollElemNames, RollEnumOptions) ); + List ChannelNeutralElemNames = new ArrayList(); + ChannelNeutralElemNames.add("Throttle"); + ChannelNeutralElemNames.add("Roll"); + ChannelNeutralElemNames.add("Pitch"); + ChannelNeutralElemNames.add("Yaw"); + ChannelNeutralElemNames.add("FlightMode"); + ChannelNeutralElemNames.add("Collective"); + ChannelNeutralElemNames.add("Accessory0"); + ChannelNeutralElemNames.add("Accessory1"); + ChannelNeutralElemNames.add("Accessory2"); + fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); - List PitchElemNames = new ArrayList(); - PitchElemNames.add("0"); - List PitchEnumOptions = new ArrayList(); - PitchEnumOptions.add("Channel1"); - PitchEnumOptions.add("Channel2"); - PitchEnumOptions.add("Channel3"); - PitchEnumOptions.add("Channel4"); - PitchEnumOptions.add("Channel5"); - PitchEnumOptions.add("Channel6"); - PitchEnumOptions.add("Channel7"); - PitchEnumOptions.add("Channel8"); - PitchEnumOptions.add("None"); - fields.add( new UAVObjectField("Pitch", "channel", UAVObjectField.FieldType.ENUM, PitchElemNames, PitchEnumOptions) ); + List ChannelMaxElemNames = new ArrayList(); + ChannelMaxElemNames.add("Throttle"); + ChannelMaxElemNames.add("Roll"); + ChannelMaxElemNames.add("Pitch"); + ChannelMaxElemNames.add("Yaw"); + ChannelMaxElemNames.add("FlightMode"); + ChannelMaxElemNames.add("Collective"); + ChannelMaxElemNames.add("Accessory0"); + ChannelMaxElemNames.add("Accessory1"); + ChannelMaxElemNames.add("Accessory2"); + fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); - List YawElemNames = new ArrayList(); - YawElemNames.add("0"); - List YawEnumOptions = new ArrayList(); - YawEnumOptions.add("Channel1"); - YawEnumOptions.add("Channel2"); - YawEnumOptions.add("Channel3"); - YawEnumOptions.add("Channel4"); - YawEnumOptions.add("Channel5"); - YawEnumOptions.add("Channel6"); - YawEnumOptions.add("Channel7"); - YawEnumOptions.add("Channel8"); - YawEnumOptions.add("None"); - fields.add( new UAVObjectField("Yaw", "channel", UAVObjectField.FieldType.ENUM, YawElemNames, YawEnumOptions) ); + List ArmedTimeoutElemNames = new ArrayList(); + ArmedTimeoutElemNames.add("0"); + fields.add( new UAVObjectField("ArmedTimeout", "ms", UAVObjectField.FieldType.UINT16, ArmedTimeoutElemNames, null) ); - List ThrottleElemNames = new ArrayList(); - ThrottleElemNames.add("0"); - List ThrottleEnumOptions = new ArrayList(); - ThrottleEnumOptions.add("Channel1"); - ThrottleEnumOptions.add("Channel2"); - ThrottleEnumOptions.add("Channel3"); - ThrottleEnumOptions.add("Channel4"); - ThrottleEnumOptions.add("Channel5"); - ThrottleEnumOptions.add("Channel6"); - ThrottleEnumOptions.add("Channel7"); - ThrottleEnumOptions.add("Channel8"); - ThrottleEnumOptions.add("None"); - fields.add( new UAVObjectField("Throttle", "channel", UAVObjectField.FieldType.ENUM, ThrottleElemNames, ThrottleEnumOptions) ); + List ChannelGroupsElemNames = new ArrayList(); + ChannelGroupsElemNames.add("Throttle"); + ChannelGroupsElemNames.add("Roll"); + ChannelGroupsElemNames.add("Pitch"); + ChannelGroupsElemNames.add("Yaw"); + ChannelGroupsElemNames.add("FlightMode"); + ChannelGroupsElemNames.add("Collective"); + ChannelGroupsElemNames.add("Accessory0"); + ChannelGroupsElemNames.add("Accessory1"); + ChannelGroupsElemNames.add("Accessory2"); + List ChannelGroupsEnumOptions = new ArrayList(); + ChannelGroupsEnumOptions.add("PWM"); + ChannelGroupsEnumOptions.add("PPM"); + ChannelGroupsEnumOptions.add("DSM (MainPort)"); + ChannelGroupsEnumOptions.add("DSM (FlexiPort)"); + ChannelGroupsEnumOptions.add("S.Bus"); + ChannelGroupsEnumOptions.add("GCS"); + ChannelGroupsEnumOptions.add("None"); + fields.add( new UAVObjectField("ChannelGroups", "Channel Group", UAVObjectField.FieldType.ENUM, ChannelGroupsElemNames, ChannelGroupsEnumOptions) ); - List FlightModeElemNames = new ArrayList(); - FlightModeElemNames.add("0"); - List FlightModeEnumOptions = new ArrayList(); - FlightModeEnumOptions.add("Channel1"); - FlightModeEnumOptions.add("Channel2"); - FlightModeEnumOptions.add("Channel3"); - FlightModeEnumOptions.add("Channel4"); - FlightModeEnumOptions.add("Channel5"); - FlightModeEnumOptions.add("Channel6"); - FlightModeEnumOptions.add("Channel7"); - FlightModeEnumOptions.add("Channel8"); - FlightModeEnumOptions.add("None"); - fields.add( new UAVObjectField("FlightMode", "channel", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); - - List Accessory1ElemNames = new ArrayList(); - Accessory1ElemNames.add("0"); - List Accessory1EnumOptions = new ArrayList(); - Accessory1EnumOptions.add("Channel1"); - Accessory1EnumOptions.add("Channel2"); - Accessory1EnumOptions.add("Channel3"); - Accessory1EnumOptions.add("Channel4"); - Accessory1EnumOptions.add("Channel5"); - Accessory1EnumOptions.add("Channel6"); - Accessory1EnumOptions.add("Channel7"); - Accessory1EnumOptions.add("Channel8"); - Accessory1EnumOptions.add("None"); - fields.add( new UAVObjectField("Accessory1", "channel", UAVObjectField.FieldType.ENUM, Accessory1ElemNames, Accessory1EnumOptions) ); - - List Accessory2ElemNames = new ArrayList(); - Accessory2ElemNames.add("0"); - List Accessory2EnumOptions = new ArrayList(); - Accessory2EnumOptions.add("Channel1"); - Accessory2EnumOptions.add("Channel2"); - Accessory2EnumOptions.add("Channel3"); - Accessory2EnumOptions.add("Channel4"); - Accessory2EnumOptions.add("Channel5"); - Accessory2EnumOptions.add("Channel6"); - Accessory2EnumOptions.add("Channel7"); - Accessory2EnumOptions.add("Channel8"); - Accessory2EnumOptions.add("None"); - fields.add( new UAVObjectField("Accessory2", "channel", UAVObjectField.FieldType.ENUM, Accessory2ElemNames, Accessory2EnumOptions) ); - - List Accessory3ElemNames = new ArrayList(); - Accessory3ElemNames.add("0"); - List Accessory3EnumOptions = new ArrayList(); - Accessory3EnumOptions.add("Channel1"); - Accessory3EnumOptions.add("Channel2"); - Accessory3EnumOptions.add("Channel3"); - Accessory3EnumOptions.add("Channel4"); - Accessory3EnumOptions.add("Channel5"); - Accessory3EnumOptions.add("Channel6"); - Accessory3EnumOptions.add("Channel7"); - Accessory3EnumOptions.add("Channel8"); - Accessory3EnumOptions.add("None"); - fields.add( new UAVObjectField("Accessory3", "channel", UAVObjectField.FieldType.ENUM, Accessory3ElemNames, Accessory3EnumOptions) ); + List ChannelNumberElemNames = new ArrayList(); + ChannelNumberElemNames.add("Throttle"); + ChannelNumberElemNames.add("Roll"); + ChannelNumberElemNames.add("Pitch"); + ChannelNumberElemNames.add("Yaw"); + ChannelNumberElemNames.add("FlightMode"); + ChannelNumberElemNames.add("Collective"); + ChannelNumberElemNames.add("Accessory0"); + ChannelNumberElemNames.add("Accessory1"); + ChannelNumberElemNames.add("Accessory2"); + fields.add( new UAVObjectField("ChannelNumber", "channel", UAVObjectField.FieldType.UINT8, ChannelNumberElemNames, null) ); List ArmingElemNames = new ArrayList(); ArmingElemNames.add("0"); @@ -192,6 +144,8 @@ public class ManualControlSettings extends UAVDataObject { Stabilization1SettingsEnumOptions.add("None"); Stabilization1SettingsEnumOptions.add("Rate"); Stabilization1SettingsEnumOptions.add("Attitude"); + Stabilization1SettingsEnumOptions.add("AxisLock"); + Stabilization1SettingsEnumOptions.add("WeakLeveling"); fields.add( new UAVObjectField("Stabilization1Settings", "", UAVObjectField.FieldType.ENUM, Stabilization1SettingsElemNames, Stabilization1SettingsEnumOptions) ); List Stabilization2SettingsElemNames = new ArrayList(); @@ -202,6 +156,8 @@ public class ManualControlSettings extends UAVDataObject { Stabilization2SettingsEnumOptions.add("None"); Stabilization2SettingsEnumOptions.add("Rate"); Stabilization2SettingsEnumOptions.add("Attitude"); + Stabilization2SettingsEnumOptions.add("AxisLock"); + Stabilization2SettingsEnumOptions.add("WeakLeveling"); fields.add( new UAVObjectField("Stabilization2Settings", "", UAVObjectField.FieldType.ENUM, Stabilization2SettingsElemNames, Stabilization2SettingsEnumOptions) ); List Stabilization3SettingsElemNames = new ArrayList(); @@ -212,6 +168,8 @@ public class ManualControlSettings extends UAVDataObject { Stabilization3SettingsEnumOptions.add("None"); Stabilization3SettingsEnumOptions.add("Rate"); Stabilization3SettingsEnumOptions.add("Attitude"); + Stabilization3SettingsEnumOptions.add("AxisLock"); + Stabilization3SettingsEnumOptions.add("WeakLeveling"); fields.add( new UAVObjectField("Stabilization3Settings", "", UAVObjectField.FieldType.ENUM, Stabilization3SettingsElemNames, Stabilization3SettingsEnumOptions) ); List FlightModePositionElemNames = new ArrayList(); @@ -227,43 +185,6 @@ public class ManualControlSettings extends UAVDataObject { FlightModePositionEnumOptions.add("PositionHold"); fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); - List ChannelMaxElemNames = new ArrayList(); - ChannelMaxElemNames.add("0"); - ChannelMaxElemNames.add("1"); - ChannelMaxElemNames.add("2"); - ChannelMaxElemNames.add("3"); - ChannelMaxElemNames.add("4"); - ChannelMaxElemNames.add("5"); - ChannelMaxElemNames.add("6"); - ChannelMaxElemNames.add("7"); - fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); - - List ChannelNeutralElemNames = new ArrayList(); - ChannelNeutralElemNames.add("0"); - ChannelNeutralElemNames.add("1"); - ChannelNeutralElemNames.add("2"); - ChannelNeutralElemNames.add("3"); - ChannelNeutralElemNames.add("4"); - ChannelNeutralElemNames.add("5"); - ChannelNeutralElemNames.add("6"); - ChannelNeutralElemNames.add("7"); - fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); - - List ChannelMinElemNames = new ArrayList(); - ChannelMinElemNames.add("0"); - ChannelMinElemNames.add("1"); - ChannelMinElemNames.add("2"); - ChannelMinElemNames.add("3"); - ChannelMinElemNames.add("4"); - ChannelMinElemNames.add("5"); - ChannelMinElemNames.add("6"); - ChannelMinElemNames.add("7"); - fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); - - List ArmedTimeoutElemNames = new ArrayList(); - ArmedTimeoutElemNames.add("0"); - fields.add( new UAVObjectField("ArmedTimeout", "ms", UAVObjectField.FieldType.UINT16, ArmedTimeoutElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -309,44 +230,6 @@ public class ManualControlSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("InputMode").setValue("PWM"); - getField("Roll").setValue("Channel1"); - getField("Pitch").setValue("Channel2"); - getField("Yaw").setValue("Channel3"); - getField("Throttle").setValue("Channel4"); - getField("FlightMode").setValue("Channel5"); - getField("Accessory1").setValue("None"); - getField("Accessory2").setValue("None"); - getField("Accessory3").setValue("None"); - getField("Arming").setValue("Always Disarmed"); - getField("Stabilization1Settings").setValue("Attitude",0); - getField("Stabilization1Settings").setValue("Attitude",1); - getField("Stabilization1Settings").setValue("Attitude",2); - getField("Stabilization2Settings").setValue("Attitude",0); - getField("Stabilization2Settings").setValue("Attitude",1); - getField("Stabilization2Settings").setValue("Attitude",2); - getField("Stabilization3Settings").setValue("Attitude",0); - getField("Stabilization3Settings").setValue("Attitude",1); - getField("Stabilization3Settings").setValue("Attitude",2); - getField("FlightModePosition").setValue("Manual",0); - getField("FlightModePosition").setValue("Manual",1); - getField("FlightModePosition").setValue("Manual",2); - getField("ChannelMax").setValue(2000,0); - getField("ChannelMax").setValue(2000,1); - getField("ChannelMax").setValue(2000,2); - getField("ChannelMax").setValue(2000,3); - getField("ChannelMax").setValue(2000,4); - getField("ChannelMax").setValue(2000,5); - getField("ChannelMax").setValue(2000,6); - getField("ChannelMax").setValue(2000,7); - getField("ChannelNeutral").setValue(1500,0); - getField("ChannelNeutral").setValue(1500,1); - getField("ChannelNeutral").setValue(1500,2); - getField("ChannelNeutral").setValue(1500,3); - getField("ChannelNeutral").setValue(1500,4); - getField("ChannelNeutral").setValue(1500,5); - getField("ChannelNeutral").setValue(1500,6); - getField("ChannelNeutral").setValue(1500,7); getField("ChannelMin").setValue(1000,0); getField("ChannelMin").setValue(1000,1); getField("ChannelMin").setValue(1000,2); @@ -355,7 +238,57 @@ public class ManualControlSettings extends UAVDataObject { getField("ChannelMin").setValue(1000,5); getField("ChannelMin").setValue(1000,6); getField("ChannelMin").setValue(1000,7); + getField("ChannelMin").setValue(1000,8); + getField("ChannelNeutral").setValue(1500,0); + getField("ChannelNeutral").setValue(1500,1); + getField("ChannelNeutral").setValue(1500,2); + getField("ChannelNeutral").setValue(1500,3); + getField("ChannelNeutral").setValue(1500,4); + getField("ChannelNeutral").setValue(1500,5); + getField("ChannelNeutral").setValue(1500,6); + getField("ChannelNeutral").setValue(1500,7); + getField("ChannelNeutral").setValue(1500,8); + getField("ChannelMax").setValue(2000,0); + getField("ChannelMax").setValue(2000,1); + getField("ChannelMax").setValue(2000,2); + getField("ChannelMax").setValue(2000,3); + getField("ChannelMax").setValue(2000,4); + getField("ChannelMax").setValue(2000,5); + getField("ChannelMax").setValue(2000,6); + getField("ChannelMax").setValue(2000,7); + getField("ChannelMax").setValue(2000,8); getField("ArmedTimeout").setValue(30000); + getField("ChannelGroups").setValue("None",0); + getField("ChannelGroups").setValue("None",1); + getField("ChannelGroups").setValue("None",2); + getField("ChannelGroups").setValue("None",3); + getField("ChannelGroups").setValue("None",4); + getField("ChannelGroups").setValue("None",5); + getField("ChannelGroups").setValue("None",6); + getField("ChannelGroups").setValue("None",7); + getField("ChannelGroups").setValue("None",8); + getField("ChannelNumber").setValue(0,0); + getField("ChannelNumber").setValue(0,1); + getField("ChannelNumber").setValue(0,2); + getField("ChannelNumber").setValue(0,3); + getField("ChannelNumber").setValue(0,4); + getField("ChannelNumber").setValue(0,5); + getField("ChannelNumber").setValue(0,6); + getField("ChannelNumber").setValue(0,7); + getField("ChannelNumber").setValue(0,8); + getField("Arming").setValue("Always Disarmed"); + getField("Stabilization1Settings").setValue("Attitude",0); + getField("Stabilization1Settings").setValue("Attitude",1); + getField("Stabilization1Settings").setValue("Rate",2); + getField("Stabilization2Settings").setValue("Attitude",0); + getField("Stabilization2Settings").setValue("Attitude",1); + getField("Stabilization2Settings").setValue("Rate",2); + getField("Stabilization3Settings").setValue("Attitude",0); + getField("Stabilization3Settings").setValue("Attitude",1); + getField("Stabilization3Settings").setValue("Rate",2); + getField("FlightModePosition").setValue("Manual",0); + getField("FlightModePosition").setValue("Stabilized1",1); + getField("FlightModePosition").setValue("Stabilized2",2); } @@ -384,7 +317,7 @@ public class ManualControlSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x2B82102; + protected static final int OBJID = 0x24959BB0; protected static final String NAME = "ManualControlSettings"; protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java index 9aa87d49e..76841d8ff 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java @@ -83,12 +83,37 @@ public class MixerSettings extends UAVDataObject { ThrottleCurve2ElemNames.add("100"); fields.add( new UAVObjectField("ThrottleCurve2", "percent", UAVObjectField.FieldType.FLOAT32, ThrottleCurve2ElemNames, null) ); + List Curve2SourceElemNames = new ArrayList(); + Curve2SourceElemNames.add("0"); + List Curve2SourceEnumOptions = new ArrayList(); + Curve2SourceEnumOptions.add("Throttle"); + Curve2SourceEnumOptions.add("Roll"); + Curve2SourceEnumOptions.add("Pitch"); + Curve2SourceEnumOptions.add("Yaw"); + Curve2SourceEnumOptions.add("Collective"); + Curve2SourceEnumOptions.add("Accessory0"); + Curve2SourceEnumOptions.add("Accessory1"); + Curve2SourceEnumOptions.add("Accessory2"); + Curve2SourceEnumOptions.add("Accessory3"); + Curve2SourceEnumOptions.add("Accessory4"); + Curve2SourceEnumOptions.add("Accessory5"); + fields.add( new UAVObjectField("Curve2Source", "", UAVObjectField.FieldType.ENUM, Curve2SourceElemNames, Curve2SourceEnumOptions) ); + List Mixer1TypeElemNames = new ArrayList(); Mixer1TypeElemNames.add("0"); List Mixer1TypeEnumOptions = new ArrayList(); Mixer1TypeEnumOptions.add("Disabled"); Mixer1TypeEnumOptions.add("Motor"); Mixer1TypeEnumOptions.add("Servo"); + Mixer1TypeEnumOptions.add("CameraRoll"); + Mixer1TypeEnumOptions.add("CameraPitch"); + Mixer1TypeEnumOptions.add("CameraYaw"); + Mixer1TypeEnumOptions.add("Accessory0"); + Mixer1TypeEnumOptions.add("Accessory1"); + Mixer1TypeEnumOptions.add("Accessory2"); + Mixer1TypeEnumOptions.add("Accessory3"); + Mixer1TypeEnumOptions.add("Accessory4"); + Mixer1TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer1Type", "", UAVObjectField.FieldType.ENUM, Mixer1TypeElemNames, Mixer1TypeEnumOptions) ); List Mixer1VectorElemNames = new ArrayList(); @@ -105,6 +130,15 @@ public class MixerSettings extends UAVDataObject { Mixer2TypeEnumOptions.add("Disabled"); Mixer2TypeEnumOptions.add("Motor"); Mixer2TypeEnumOptions.add("Servo"); + Mixer2TypeEnumOptions.add("CameraRoll"); + Mixer2TypeEnumOptions.add("CameraPitch"); + Mixer2TypeEnumOptions.add("CameraYaw"); + Mixer2TypeEnumOptions.add("Accessory0"); + Mixer2TypeEnumOptions.add("Accessory1"); + Mixer2TypeEnumOptions.add("Accessory2"); + Mixer2TypeEnumOptions.add("Accessory3"); + Mixer2TypeEnumOptions.add("Accessory4"); + Mixer2TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer2Type", "", UAVObjectField.FieldType.ENUM, Mixer2TypeElemNames, Mixer2TypeEnumOptions) ); List Mixer2VectorElemNames = new ArrayList(); @@ -121,6 +155,15 @@ public class MixerSettings extends UAVDataObject { Mixer3TypeEnumOptions.add("Disabled"); Mixer3TypeEnumOptions.add("Motor"); Mixer3TypeEnumOptions.add("Servo"); + Mixer3TypeEnumOptions.add("CameraRoll"); + Mixer3TypeEnumOptions.add("CameraPitch"); + Mixer3TypeEnumOptions.add("CameraYaw"); + Mixer3TypeEnumOptions.add("Accessory0"); + Mixer3TypeEnumOptions.add("Accessory1"); + Mixer3TypeEnumOptions.add("Accessory2"); + Mixer3TypeEnumOptions.add("Accessory3"); + Mixer3TypeEnumOptions.add("Accessory4"); + Mixer3TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer3Type", "", UAVObjectField.FieldType.ENUM, Mixer3TypeElemNames, Mixer3TypeEnumOptions) ); List Mixer3VectorElemNames = new ArrayList(); @@ -137,6 +180,15 @@ public class MixerSettings extends UAVDataObject { Mixer4TypeEnumOptions.add("Disabled"); Mixer4TypeEnumOptions.add("Motor"); Mixer4TypeEnumOptions.add("Servo"); + Mixer4TypeEnumOptions.add("CameraRoll"); + Mixer4TypeEnumOptions.add("CameraPitch"); + Mixer4TypeEnumOptions.add("CameraYaw"); + Mixer4TypeEnumOptions.add("Accessory0"); + Mixer4TypeEnumOptions.add("Accessory1"); + Mixer4TypeEnumOptions.add("Accessory2"); + Mixer4TypeEnumOptions.add("Accessory3"); + Mixer4TypeEnumOptions.add("Accessory4"); + Mixer4TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer4Type", "", UAVObjectField.FieldType.ENUM, Mixer4TypeElemNames, Mixer4TypeEnumOptions) ); List Mixer4VectorElemNames = new ArrayList(); @@ -153,6 +205,15 @@ public class MixerSettings extends UAVDataObject { Mixer5TypeEnumOptions.add("Disabled"); Mixer5TypeEnumOptions.add("Motor"); Mixer5TypeEnumOptions.add("Servo"); + Mixer5TypeEnumOptions.add("CameraRoll"); + Mixer5TypeEnumOptions.add("CameraPitch"); + Mixer5TypeEnumOptions.add("CameraYaw"); + Mixer5TypeEnumOptions.add("Accessory0"); + Mixer5TypeEnumOptions.add("Accessory1"); + Mixer5TypeEnumOptions.add("Accessory2"); + Mixer5TypeEnumOptions.add("Accessory3"); + Mixer5TypeEnumOptions.add("Accessory4"); + Mixer5TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer5Type", "", UAVObjectField.FieldType.ENUM, Mixer5TypeElemNames, Mixer5TypeEnumOptions) ); List Mixer5VectorElemNames = new ArrayList(); @@ -169,6 +230,15 @@ public class MixerSettings extends UAVDataObject { Mixer6TypeEnumOptions.add("Disabled"); Mixer6TypeEnumOptions.add("Motor"); Mixer6TypeEnumOptions.add("Servo"); + Mixer6TypeEnumOptions.add("CameraRoll"); + Mixer6TypeEnumOptions.add("CameraPitch"); + Mixer6TypeEnumOptions.add("CameraYaw"); + Mixer6TypeEnumOptions.add("Accessory0"); + Mixer6TypeEnumOptions.add("Accessory1"); + Mixer6TypeEnumOptions.add("Accessory2"); + Mixer6TypeEnumOptions.add("Accessory3"); + Mixer6TypeEnumOptions.add("Accessory4"); + Mixer6TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer6Type", "", UAVObjectField.FieldType.ENUM, Mixer6TypeElemNames, Mixer6TypeEnumOptions) ); List Mixer6VectorElemNames = new ArrayList(); @@ -185,6 +255,15 @@ public class MixerSettings extends UAVDataObject { Mixer7TypeEnumOptions.add("Disabled"); Mixer7TypeEnumOptions.add("Motor"); Mixer7TypeEnumOptions.add("Servo"); + Mixer7TypeEnumOptions.add("CameraRoll"); + Mixer7TypeEnumOptions.add("CameraPitch"); + Mixer7TypeEnumOptions.add("CameraYaw"); + Mixer7TypeEnumOptions.add("Accessory0"); + Mixer7TypeEnumOptions.add("Accessory1"); + Mixer7TypeEnumOptions.add("Accessory2"); + Mixer7TypeEnumOptions.add("Accessory3"); + Mixer7TypeEnumOptions.add("Accessory4"); + Mixer7TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer7Type", "", UAVObjectField.FieldType.ENUM, Mixer7TypeElemNames, Mixer7TypeEnumOptions) ); List Mixer7VectorElemNames = new ArrayList(); @@ -201,6 +280,15 @@ public class MixerSettings extends UAVDataObject { Mixer8TypeEnumOptions.add("Disabled"); Mixer8TypeEnumOptions.add("Motor"); Mixer8TypeEnumOptions.add("Servo"); + Mixer8TypeEnumOptions.add("CameraRoll"); + Mixer8TypeEnumOptions.add("CameraPitch"); + Mixer8TypeEnumOptions.add("CameraYaw"); + Mixer8TypeEnumOptions.add("Accessory0"); + Mixer8TypeEnumOptions.add("Accessory1"); + Mixer8TypeEnumOptions.add("Accessory2"); + Mixer8TypeEnumOptions.add("Accessory3"); + Mixer8TypeEnumOptions.add("Accessory4"); + Mixer8TypeEnumOptions.add("Accessory5"); fields.add( new UAVObjectField("Mixer8Type", "", UAVObjectField.FieldType.ENUM, Mixer8TypeElemNames, Mixer8TypeEnumOptions) ); List Mixer8VectorElemNames = new ArrayList(); @@ -211,6 +299,56 @@ public class MixerSettings extends UAVDataObject { Mixer8VectorElemNames.add("Yaw"); fields.add( new UAVObjectField("Mixer8Vector", "", UAVObjectField.FieldType.INT8, Mixer8VectorElemNames, null) ); + List Mixer9TypeElemNames = new ArrayList(); + Mixer9TypeElemNames.add("0"); + List Mixer9TypeEnumOptions = new ArrayList(); + Mixer9TypeEnumOptions.add("Disabled"); + Mixer9TypeEnumOptions.add("Motor"); + Mixer9TypeEnumOptions.add("Servo"); + Mixer9TypeEnumOptions.add("CameraRoll"); + Mixer9TypeEnumOptions.add("CameraPitch"); + Mixer9TypeEnumOptions.add("CameraYaw"); + Mixer9TypeEnumOptions.add("Accessory0"); + Mixer9TypeEnumOptions.add("Accessory1"); + Mixer9TypeEnumOptions.add("Accessory2"); + Mixer9TypeEnumOptions.add("Accessory3"); + Mixer9TypeEnumOptions.add("Accessory4"); + Mixer9TypeEnumOptions.add("Accessory5"); + fields.add( new UAVObjectField("Mixer9Type", "", UAVObjectField.FieldType.ENUM, Mixer9TypeElemNames, Mixer9TypeEnumOptions) ); + + List Mixer9VectorElemNames = new ArrayList(); + Mixer9VectorElemNames.add("ThrottleCurve1"); + Mixer9VectorElemNames.add("ThrottleCurve2"); + Mixer9VectorElemNames.add("Roll"); + Mixer9VectorElemNames.add("Pitch"); + Mixer9VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer9Vector", "", UAVObjectField.FieldType.INT8, Mixer9VectorElemNames, null) ); + + List Mixer10TypeElemNames = new ArrayList(); + Mixer10TypeElemNames.add("0"); + List Mixer10TypeEnumOptions = new ArrayList(); + Mixer10TypeEnumOptions.add("Disabled"); + Mixer10TypeEnumOptions.add("Motor"); + Mixer10TypeEnumOptions.add("Servo"); + Mixer10TypeEnumOptions.add("CameraRoll"); + Mixer10TypeEnumOptions.add("CameraPitch"); + Mixer10TypeEnumOptions.add("CameraYaw"); + Mixer10TypeEnumOptions.add("Accessory0"); + Mixer10TypeEnumOptions.add("Accessory1"); + Mixer10TypeEnumOptions.add("Accessory2"); + Mixer10TypeEnumOptions.add("Accessory3"); + Mixer10TypeEnumOptions.add("Accessory4"); + Mixer10TypeEnumOptions.add("Accessory5"); + fields.add( new UAVObjectField("Mixer10Type", "", UAVObjectField.FieldType.ENUM, Mixer10TypeElemNames, Mixer10TypeEnumOptions) ); + + List Mixer10VectorElemNames = new ArrayList(); + Mixer10VectorElemNames.add("ThrottleCurve1"); + Mixer10VectorElemNames.add("ThrottleCurve2"); + Mixer10VectorElemNames.add("Roll"); + Mixer10VectorElemNames.add("Pitch"); + Mixer10VectorElemNames.add("Yaw"); + fields.add( new UAVObjectField("Mixer10Vector", "", UAVObjectField.FieldType.INT8, Mixer10VectorElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -261,15 +399,16 @@ public class MixerSettings extends UAVDataObject { getField("AccelTime").setValue(0); getField("DecelTime").setValue(0); getField("ThrottleCurve1").setValue(0,0); - getField("ThrottleCurve1").setValue(0.25,1); - getField("ThrottleCurve1").setValue(0.5,2); - getField("ThrottleCurve1").setValue(0.75,3); - getField("ThrottleCurve1").setValue(1,4); + getField("ThrottleCurve1").setValue(0,1); + getField("ThrottleCurve1").setValue(0,2); + getField("ThrottleCurve1").setValue(0,3); + getField("ThrottleCurve1").setValue(0,4); getField("ThrottleCurve2").setValue(0,0); getField("ThrottleCurve2").setValue(0.25,1); getField("ThrottleCurve2").setValue(0.5,2); getField("ThrottleCurve2").setValue(0.75,3); getField("ThrottleCurve2").setValue(1,4); + getField("Curve2Source").setValue("Throttle"); getField("Mixer1Type").setValue("Disabled"); getField("Mixer1Vector").setValue(0,0); getField("Mixer1Vector").setValue(0,1); @@ -318,6 +457,18 @@ public class MixerSettings extends UAVDataObject { getField("Mixer8Vector").setValue(0,2); getField("Mixer8Vector").setValue(0,3); getField("Mixer8Vector").setValue(0,4); + getField("Mixer9Type").setValue("Disabled"); + getField("Mixer9Vector").setValue(0,0); + getField("Mixer9Vector").setValue(0,1); + getField("Mixer9Vector").setValue(0,2); + getField("Mixer9Vector").setValue(0,3); + getField("Mixer9Vector").setValue(0,4); + getField("Mixer10Type").setValue("Disabled"); + getField("Mixer10Vector").setValue(0,0); + getField("Mixer10Vector").setValue(0,1); + getField("Mixer10Vector").setValue(0,2); + getField("Mixer10Vector").setValue(0,3); + getField("Mixer10Vector").setValue(0,4); } @@ -346,7 +497,7 @@ public class MixerSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x4FAE374E; + protected static final int OBJID = 0x5D16D6C4; protected static final String NAME = "MixerSettings"; protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java index fbd405b40..106220a8c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java @@ -156,7 +156,7 @@ public class MixerStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF6A33F10; + protected static final int OBJID = 0x11CFB4E6; protected static final String NAME = "MixerStatus"; protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java index f16ddd199..3b09dd1f8 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java @@ -136,7 +136,7 @@ public class NedAccel extends UAVDataObject { } // Constants - protected static final int OBJID = 0x8E852CE8; + protected static final int OBJID = 0x7C7F5BC0; protected static final String NAME = "NedAccel"; protected static String DESCRIPTION = "The projection of acceleration in the NED reference frame used by @ref Guidance."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java index 2a09c2b40..dccd85d36 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java @@ -51,12 +51,23 @@ public class ObjectPersistence extends UAVDataObject { List fields = new ArrayList(); + List ObjectIDElemNames = new ArrayList(); + ObjectIDElemNames.add("0"); + fields.add( new UAVObjectField("ObjectID", "", UAVObjectField.FieldType.UINT32, ObjectIDElemNames, null) ); + + List InstanceIDElemNames = new ArrayList(); + InstanceIDElemNames.add("0"); + fields.add( new UAVObjectField("InstanceID", "", UAVObjectField.FieldType.UINT32, InstanceIDElemNames, null) ); + List OperationElemNames = new ArrayList(); OperationElemNames.add("0"); List OperationEnumOptions = new ArrayList(); + OperationEnumOptions.add("NOP"); OperationEnumOptions.add("Load"); OperationEnumOptions.add("Save"); OperationEnumOptions.add("Delete"); + OperationEnumOptions.add("FullErase"); + OperationEnumOptions.add("Completed"); fields.add( new UAVObjectField("Operation", "", UAVObjectField.FieldType.ENUM, OperationElemNames, OperationEnumOptions) ); List SelectionElemNames = new ArrayList(); @@ -68,14 +79,6 @@ public class ObjectPersistence extends UAVDataObject { SelectionEnumOptions.add("AllObjects"); fields.add( new UAVObjectField("Selection", "", UAVObjectField.FieldType.ENUM, SelectionElemNames, SelectionEnumOptions) ); - List ObjectIDElemNames = new ArrayList(); - ObjectIDElemNames.add("0"); - fields.add( new UAVObjectField("ObjectID", "", UAVObjectField.FieldType.UINT32, ObjectIDElemNames, null) ); - - List InstanceIDElemNames = new ArrayList(); - InstanceIDElemNames.add("0"); - fields.add( new UAVObjectField("InstanceID", "", UAVObjectField.FieldType.UINT32, InstanceIDElemNames, null) ); - // Compute the number of bytes for this object int numBytes = 0; @@ -106,7 +109,7 @@ public class ObjectPersistence extends UAVDataObject { metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; metadata.flightTelemetryUpdatePeriod = 0; metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; @@ -149,7 +152,7 @@ public class ObjectPersistence extends UAVDataObject { } // Constants - protected static final int OBJID = 0x22216832; + protected static final int OBJID = 0xF69AD8B8; protected static final String NAME = "ObjectPersistence"; protected static String DESCRIPTION = "Someone who knows please enter this"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java index 444009f90..ac30ad4f5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java @@ -136,7 +136,7 @@ public class PositionActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0xE0739636; + protected static final int OBJID = 0xF9691DA4; protected static final String NAME = "PositionActual"; protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java index 5cf51df71..2ff5a5586 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java @@ -136,7 +136,7 @@ public class PositionDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x2FC4E5BA; + protected static final int OBJID = 0x33C9EAB4; protected static final String NAME = "PositionDesired"; protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java index 7164c0957..ddeacd8d4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java @@ -136,7 +136,7 @@ public class RateDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0xBA41B51C; + protected static final int OBJID = 0xCE8C826; protected static final String NAME = "RateDesired"; protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java similarity index 61% rename from androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java rename to androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java index 6af673930..a40b27e38 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BatterySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java @@ -5,7 +5,7 @@ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief Template for an uavobject in java * This is a autogenerated file!! Do not modify and expect a result. - * Battery configuration information. + * Monitors which receiver channels have been active within the last second. * * @see The GNU Public License (GPL) Version 3 * @@ -39,40 +39,33 @@ import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectField; /** -Battery configuration information. +Monitors which receiver channels have been active within the last second. -generated from batterysettings.xml +generated from receiveractivity.xml **/ -public class BatterySettings extends UAVDataObject { +public class ReceiverActivity extends UAVDataObject { - public BatterySettings() { + public ReceiverActivity() { super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); List fields = new ArrayList(); - List BatteryVoltageElemNames = new ArrayList(); - BatteryVoltageElemNames.add("0"); - fields.add( new UAVObjectField("BatteryVoltage", "V", UAVObjectField.FieldType.FLOAT32, BatteryVoltageElemNames, null) ); + List ActiveGroupElemNames = new ArrayList(); + ActiveGroupElemNames.add("0"); + List ActiveGroupEnumOptions = new ArrayList(); + ActiveGroupEnumOptions.add("PWM"); + ActiveGroupEnumOptions.add("PPM"); + ActiveGroupEnumOptions.add("DSM (MainPort)"); + ActiveGroupEnumOptions.add("DSM (FlexiPort)"); + ActiveGroupEnumOptions.add("S.Bus"); + ActiveGroupEnumOptions.add("GCS"); + ActiveGroupEnumOptions.add("None"); + fields.add( new UAVObjectField("ActiveGroup", "Channel Group", UAVObjectField.FieldType.ENUM, ActiveGroupElemNames, ActiveGroupEnumOptions) ); - List BatteryCapacityElemNames = new ArrayList(); - BatteryCapacityElemNames.add("0"); - fields.add( new UAVObjectField("BatteryCapacity", "mAh", UAVObjectField.FieldType.UINT32, BatteryCapacityElemNames, null) ); - - List BatteryTypeElemNames = new ArrayList(); - BatteryTypeElemNames.add("0"); - List BatteryTypeEnumOptions = new ArrayList(); - BatteryTypeEnumOptions.add("LiPo"); - BatteryTypeEnumOptions.add("A123"); - BatteryTypeEnumOptions.add("LiCo"); - BatteryTypeEnumOptions.add("LiFeSO4"); - BatteryTypeEnumOptions.add("None"); - fields.add( new UAVObjectField("BatteryType", "", UAVObjectField.FieldType.ENUM, BatteryTypeElemNames, BatteryTypeEnumOptions) ); - - List CalibrationsElemNames = new ArrayList(); - CalibrationsElemNames.add("Voltage"); - CalibrationsElemNames.add("Current"); - fields.add( new UAVObjectField("Calibrations", "", UAVObjectField.FieldType.FLOAT32, CalibrationsElemNames, null) ); + List ActiveChannelElemNames = new ArrayList(); + ActiveChannelElemNames.add("0"); + fields.add( new UAVObjectField("ActiveChannel", "channel", UAVObjectField.FieldType.UINT8, ActiveChannelElemNames, null) ); // Compute the number of bytes for this object @@ -97,13 +90,13 @@ public class BatterySettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READONLY; + metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; + metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; metadata.gcsTelemetryUpdatePeriod = 0; metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; + metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; metadata.flightTelemetryUpdatePeriod = 0; @@ -119,11 +112,8 @@ public class BatterySettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("BatteryVoltage").setValue(11.1); - getField("BatteryCapacity").setValue(2200); - getField("BatteryType").setValue("LiPo"); - getField("Calibrations").setValue(1,0); - getField("Calibrations").setValue(1,1); + getField("ActiveGroup").setValue("None"); + getField("ActiveChannel").setValue(255); } @@ -135,7 +125,7 @@ public class BatterySettings extends UAVDataObject { public UAVDataObject clone(int instID) { // TODO: Need to get specific instance to clone try { - BatterySettings obj = new BatterySettings(); + ReceiverActivity obj = new ReceiverActivity(); obj.initialize(instID, this.getMetaObject()); return obj; } catch (Exception e) { @@ -146,17 +136,17 @@ public class BatterySettings extends UAVDataObject { /** * Static function to retrieve an instance of the object. */ - public BatterySettings GetInstance(UAVObjectManager objMngr, int instID) + public ReceiverActivity GetInstance(UAVObjectManager objMngr, int instID) { - return (BatterySettings)(objMngr.getObject(BatterySettings.OBJID, instID)); + return (ReceiverActivity)(objMngr.getObject(ReceiverActivity.OBJID, instID)); } // Constants - protected static final int OBJID = 0xA5FF1D9A; - protected static final String NAME = "BatterySettings"; - protected static String DESCRIPTION = "Battery configuration information."; + protected static final int OBJID = 0x1E7C53DA; + protected static final String NAME = "ReceiverActivity"; + protected static String DESCRIPTION = "Monitors which receiver channels have been active within the last second."; protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; protected static int NUMBYTES = 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java index 4e9f0b8b8..18cf6f4d6 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java @@ -128,7 +128,7 @@ public class SonarAltitude extends UAVDataObject { } // Constants - protected static final int OBJID = 0x1FDD844C; + protected static final int OBJID = 0x6C5A0CBC; protected static final String NAME = "SonarAltitude"; protected static String DESCRIPTION = "The raw data from the ultrasound sonar sensor with altitude estimate."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java index 8cba8a54c..32d2c735c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java @@ -75,6 +75,8 @@ public class StabilizationDesired extends UAVDataObject { StabilizationModeEnumOptions.add("None"); StabilizationModeEnumOptions.add("Rate"); StabilizationModeEnumOptions.add("Attitude"); + StabilizationModeEnumOptions.add("AxisLock"); + StabilizationModeEnumOptions.add("WeakLeveling"); fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); @@ -150,7 +152,7 @@ public class StabilizationDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x41AA9DC2; + protected static final int OBJID = 0xDB8FFC3C; protected static final String NAME = "StabilizationDesired"; protected static String DESCRIPTION = "The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java index 74c480e1c..ab78bdc74 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java @@ -51,18 +51,6 @@ public class StabilizationSettings extends UAVDataObject { List fields = new ArrayList(); - List RollMaxElemNames = new ArrayList(); - RollMaxElemNames.add("0"); - fields.add( new UAVObjectField("RollMax", "degrees", UAVObjectField.FieldType.UINT8, RollMaxElemNames, null) ); - - List PitchMaxElemNames = new ArrayList(); - PitchMaxElemNames.add("0"); - fields.add( new UAVObjectField("PitchMax", "degrees", UAVObjectField.FieldType.UINT8, PitchMaxElemNames, null) ); - - List YawMaxElemNames = new ArrayList(); - YawMaxElemNames.add("0"); - fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); - List ManualRateElemNames = new ArrayList(); ManualRateElemNames.add("Roll"); ManualRateElemNames.add("Pitch"); @@ -75,23 +63,26 @@ public class StabilizationSettings extends UAVDataObject { MaximumRateElemNames.add("Yaw"); fields.add( new UAVObjectField("MaximumRate", "degrees/sec", UAVObjectField.FieldType.FLOAT32, MaximumRateElemNames, null) ); - List RollRatePIElemNames = new ArrayList(); - RollRatePIElemNames.add("Kp"); - RollRatePIElemNames.add("Ki"); - RollRatePIElemNames.add("ILimit"); - fields.add( new UAVObjectField("RollRatePI", "", UAVObjectField.FieldType.FLOAT32, RollRatePIElemNames, null) ); + List RollRatePIDElemNames = new ArrayList(); + RollRatePIDElemNames.add("Kp"); + RollRatePIDElemNames.add("Ki"); + RollRatePIDElemNames.add("Kd"); + RollRatePIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("RollRatePID", "", UAVObjectField.FieldType.FLOAT32, RollRatePIDElemNames, null) ); - List PitchRatePIElemNames = new ArrayList(); - PitchRatePIElemNames.add("Kp"); - PitchRatePIElemNames.add("Ki"); - PitchRatePIElemNames.add("ILimit"); - fields.add( new UAVObjectField("PitchRatePI", "", UAVObjectField.FieldType.FLOAT32, PitchRatePIElemNames, null) ); + List PitchRatePIDElemNames = new ArrayList(); + PitchRatePIDElemNames.add("Kp"); + PitchRatePIDElemNames.add("Ki"); + PitchRatePIDElemNames.add("Kd"); + PitchRatePIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("PitchRatePID", "", UAVObjectField.FieldType.FLOAT32, PitchRatePIDElemNames, null) ); - List YawRatePIElemNames = new ArrayList(); - YawRatePIElemNames.add("Kp"); - YawRatePIElemNames.add("Ki"); - YawRatePIElemNames.add("ILimit"); - fields.add( new UAVObjectField("YawRatePI", "", UAVObjectField.FieldType.FLOAT32, YawRatePIElemNames, null) ); + List YawRatePIDElemNames = new ArrayList(); + YawRatePIDElemNames.add("Kp"); + YawRatePIDElemNames.add("Ki"); + YawRatePIDElemNames.add("Kd"); + YawRatePIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("YawRatePID", "", UAVObjectField.FieldType.FLOAT32, YawRatePIDElemNames, null) ); List RollPIElemNames = new ArrayList(); RollPIElemNames.add("Kp"); @@ -111,6 +102,45 @@ public class StabilizationSettings extends UAVDataObject { YawPIElemNames.add("ILimit"); fields.add( new UAVObjectField("YawPI", "", UAVObjectField.FieldType.FLOAT32, YawPIElemNames, null) ); + List GyroTauElemNames = new ArrayList(); + GyroTauElemNames.add("0"); + fields.add( new UAVObjectField("GyroTau", "", UAVObjectField.FieldType.FLOAT32, GyroTauElemNames, null) ); + + List WeakLevelingKpElemNames = new ArrayList(); + WeakLevelingKpElemNames.add("0"); + fields.add( new UAVObjectField("WeakLevelingKp", "(deg/s)/deg", UAVObjectField.FieldType.FLOAT32, WeakLevelingKpElemNames, null) ); + + List RollMaxElemNames = new ArrayList(); + RollMaxElemNames.add("0"); + fields.add( new UAVObjectField("RollMax", "degrees", UAVObjectField.FieldType.UINT8, RollMaxElemNames, null) ); + + List PitchMaxElemNames = new ArrayList(); + PitchMaxElemNames.add("0"); + fields.add( new UAVObjectField("PitchMax", "degrees", UAVObjectField.FieldType.UINT8, PitchMaxElemNames, null) ); + + List YawMaxElemNames = new ArrayList(); + YawMaxElemNames.add("0"); + fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); + + List MaxAxisLockElemNames = new ArrayList(); + MaxAxisLockElemNames.add("0"); + fields.add( new UAVObjectField("MaxAxisLock", "deg", UAVObjectField.FieldType.UINT8, MaxAxisLockElemNames, null) ); + + List MaxAxisLockRateElemNames = new ArrayList(); + MaxAxisLockRateElemNames.add("0"); + fields.add( new UAVObjectField("MaxAxisLockRate", "deg/s", UAVObjectField.FieldType.UINT8, MaxAxisLockRateElemNames, null) ); + + List MaxWeakLevelingRateElemNames = new ArrayList(); + MaxWeakLevelingRateElemNames.add("0"); + fields.add( new UAVObjectField("MaxWeakLevelingRate", "deg/s", UAVObjectField.FieldType.UINT8, MaxWeakLevelingRateElemNames, null) ); + + List LowThrottleZeroIntegralElemNames = new ArrayList(); + LowThrottleZeroIntegralElemNames.add("0"); + List LowThrottleZeroIntegralEnumOptions = new ArrayList(); + LowThrottleZeroIntegralEnumOptions.add("FALSE"); + LowThrottleZeroIntegralEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("LowThrottleZeroIntegral", "", UAVObjectField.FieldType.ENUM, LowThrottleZeroIntegralElemNames, LowThrottleZeroIntegralEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -156,24 +186,24 @@ public class StabilizationSettings extends UAVDataObject { */ public void setDefaultFieldValues() { - getField("RollMax").setValue(35); - getField("PitchMax").setValue(35); - getField("YawMax").setValue(35); getField("ManualRate").setValue(150,0); getField("ManualRate").setValue(150,1); getField("ManualRate").setValue(150,2); getField("MaximumRate").setValue(300,0); getField("MaximumRate").setValue(300,1); getField("MaximumRate").setValue(300,2); - getField("RollRatePI").setValue(0.0015,0); - getField("RollRatePI").setValue(0,1); - getField("RollRatePI").setValue(0.3,2); - getField("PitchRatePI").setValue(0.0015,0); - getField("PitchRatePI").setValue(0,1); - getField("PitchRatePI").setValue(0.3,2); - getField("YawRatePI").setValue(0.003,0); - getField("YawRatePI").setValue(0,1); - getField("YawRatePI").setValue(0.3,2); + getField("RollRatePID").setValue(0.002,0); + getField("RollRatePID").setValue(0,1); + getField("RollRatePID").setValue(0,2); + getField("RollRatePID").setValue(0.3,3); + getField("PitchRatePID").setValue(0.002,0); + getField("PitchRatePID").setValue(0,1); + getField("PitchRatePID").setValue(0,2); + getField("PitchRatePID").setValue(0.3,3); + getField("YawRatePID").setValue(0.0035,0); + getField("YawRatePID").setValue(0.0035,1); + getField("YawRatePID").setValue(0,2); + getField("YawRatePID").setValue(0.3,3); getField("RollPI").setValue(2,0); getField("RollPI").setValue(0,1); getField("RollPI").setValue(50,2); @@ -183,6 +213,15 @@ public class StabilizationSettings extends UAVDataObject { getField("YawPI").setValue(2,0); getField("YawPI").setValue(0,1); getField("YawPI").setValue(50,2); + getField("GyroTau").setValue(0.005); + getField("WeakLevelingKp").setValue(0.1); + getField("RollMax").setValue(55); + getField("PitchMax").setValue(55); + getField("YawMax").setValue(35); + getField("MaxAxisLock").setValue(15); + getField("MaxAxisLockRate").setValue(2); + getField("MaxWeakLevelingRate").setValue(5); + getField("LowThrottleZeroIntegral").setValue("TRUE"); } @@ -211,7 +250,7 @@ public class StabilizationSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0xE2147404; + protected static final int OBJID = 0x5F78C51E; protected static final String NAME = "StabilizationSettings"; protected static String DESCRIPTION = "PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java index e9313472c..458dd9d10 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -68,6 +68,7 @@ public class SystemAlarms extends UAVDataObject { AlarmElemNames.add("FlightTime"); AlarmElemNames.add("I2C"); AlarmElemNames.add("GPS"); + AlarmElemNames.add("BootFault"); List AlarmEnumOptions = new ArrayList(); AlarmEnumOptions.add("Uninitialised"); AlarmEnumOptions.add("OK"); @@ -106,8 +107,8 @@ public class SystemAlarms extends UAVDataObject { metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 4000; + metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + metadata.flightTelemetryUpdatePeriod = 0; metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; metadata.loggingUpdatePeriod = 1000; @@ -137,6 +138,7 @@ public class SystemAlarms extends UAVDataObject { getField("Alarm").setValue("Uninitialised",13); getField("Alarm").setValue("Uninitialised",14); getField("Alarm").setValue("Uninitialised",15); + getField("Alarm").setValue("Uninitialised",16); } @@ -165,7 +167,7 @@ public class SystemAlarms extends UAVDataObject { } // Constants - protected static final int OBJID = 0x89C3DCB2; + protected static final int OBJID = 0x737ADCF2; protected static final String NAME = "SystemAlarms"; protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java index 99bceb6ba..e3c2cf0b0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java @@ -51,6 +51,11 @@ public class SystemSettings extends UAVDataObject { List fields = new ArrayList(); + List GUIConfigDataElemNames = new ArrayList(); + GUIConfigDataElemNames.add("0"); + GUIConfigDataElemNames.add("1"); + fields.add( new UAVObjectField("GUIConfigData", "bits", UAVObjectField.FieldType.UINT32, GUIConfigDataElemNames, null) ); + List AirframeTypeElemNames = new ArrayList(); AirframeTypeElemNames.add("0"); List AirframeTypeEnumOptions = new ArrayList(); @@ -117,6 +122,8 @@ public class SystemSettings extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("GUIConfigData").setValue(0,0); + getField("GUIConfigData").setValue(0,1); getField("AirframeType").setValue("FixedWing"); } @@ -146,7 +153,7 @@ public class SystemSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x3875CEE; + protected static final int OBJID = 0x30BD5D7C; protected static final String NAME = "SystemSettings"; protected static String DESCRIPTION = "Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java index 7c34360e9..d1c51d43f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java @@ -59,6 +59,10 @@ public class SystemStats extends UAVDataObject { HeapRemainingElemNames.add("0"); fields.add( new UAVObjectField("HeapRemaining", "bytes", UAVObjectField.FieldType.UINT16, HeapRemainingElemNames, null) ); + List IRQStackRemainingElemNames = new ArrayList(); + IRQStackRemainingElemNames.add("0"); + fields.add( new UAVObjectField("IRQStackRemaining", "bytes", UAVObjectField.FieldType.UINT16, IRQStackRemainingElemNames, null) ); + List CPULoadElemNames = new ArrayList(); CPULoadElemNames.add("0"); fields.add( new UAVObjectField("CPULoad", "%", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); @@ -140,7 +144,7 @@ public class SystemStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0xAA26FFFA; + protected static final int OBJID = 0xD610A0F0; protected static final String NAME = "SystemStats"; protected static String DESCRIPTION = "CPU and memory usage from OpenPilot computer. "; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java index 3ad065b5c..54825fafe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -65,6 +65,8 @@ public class TaskInfo extends UAVDataObject { StackRemainingElemNames.add("Stabilization"); StackRemainingElemNames.add("Guidance"); StackRemainingElemNames.add("FlightPlan"); + StackRemainingElemNames.add("Com2UsbBridge"); + StackRemainingElemNames.add("Usb2ComBridge"); fields.add( new UAVObjectField("StackRemaining", "bytes", UAVObjectField.FieldType.UINT16, StackRemainingElemNames, null) ); List RunningElemNames = new ArrayList(); @@ -81,11 +83,31 @@ public class TaskInfo extends UAVDataObject { RunningElemNames.add("Stabilization"); RunningElemNames.add("Guidance"); RunningElemNames.add("FlightPlan"); + RunningElemNames.add("Com2UsbBridge"); + RunningElemNames.add("Usb2ComBridge"); List RunningEnumOptions = new ArrayList(); RunningEnumOptions.add("False"); RunningEnumOptions.add("True"); fields.add( new UAVObjectField("Running", "bool", UAVObjectField.FieldType.ENUM, RunningElemNames, RunningEnumOptions) ); + List RunningTimeElemNames = new ArrayList(); + RunningTimeElemNames.add("System"); + RunningTimeElemNames.add("Actuator"); + RunningTimeElemNames.add("Attitude"); + RunningTimeElemNames.add("TelemetryTx"); + RunningTimeElemNames.add("TelemetryTxPri"); + RunningTimeElemNames.add("TelemetryRx"); + RunningTimeElemNames.add("GPS"); + RunningTimeElemNames.add("ManualControl"); + RunningTimeElemNames.add("Altitude"); + RunningTimeElemNames.add("AHRSComms"); + RunningTimeElemNames.add("Stabilization"); + RunningTimeElemNames.add("Guidance"); + RunningTimeElemNames.add("FlightPlan"); + RunningTimeElemNames.add("Com2UsbBridge"); + RunningTimeElemNames.add("Usb2ComBridge"); + fields.add( new UAVObjectField("RunningTime", "%", UAVObjectField.FieldType.UINT8, RunningTimeElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -159,7 +181,7 @@ public class TaskInfo extends UAVDataObject { } // Constants - protected static final int OBJID = 0x50F599F0; + protected static final int OBJID = 0xE34A7C32; protected static final String NAME = "TaskInfo"; protected static String DESCRIPTION = "Task information"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java index d1d47aebb..c2cf64d49 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -28,13 +28,14 @@ package org.openpilot.uavtalk.uavobjects; -//import org.openpilot.uavtalk.uavobjects.*; +import org.openpilot.uavtalk.uavobjects.*; import org.openpilot.uavtalk.UAVObjectManager; public class UAVObjectsInitialize { public static void register(UAVObjectManager objMngr) { try { + objMngr.registerObject( new AccessoryDesired() ); objMngr.registerObject( new ActuatorCommand() ); objMngr.registerObject( new ActuatorDesired() ); objMngr.registerObject( new ActuatorSettings() ); @@ -45,19 +46,25 @@ public class UAVObjectsInitialize { objMngr.registerObject( new AttitudeRaw() ); objMngr.registerObject( new AttitudeSettings() ); objMngr.registerObject( new BaroAltitude() ); - objMngr.registerObject( new BatterySettings() ); + objMngr.registerObject( new CameraDesired() ); + objMngr.registerObject( new CameraStabSettings() ); + objMngr.registerObject( new FaultSettings() ); objMngr.registerObject( new FirmwareIAPObj() ); + objMngr.registerObject( new FlightBatterySettings() ); objMngr.registerObject( new FlightBatteryState() ); objMngr.registerObject( new FlightPlanControl() ); objMngr.registerObject( new FlightPlanSettings() ); objMngr.registerObject( new FlightPlanStatus() ); + objMngr.registerObject( new FlightStatus() ); objMngr.registerObject( new FlightTelemetryStats() ); + objMngr.registerObject( new GCSReceiver() ); objMngr.registerObject( new GCSTelemetryStats() ); objMngr.registerObject( new GPSPosition() ); objMngr.registerObject( new GPSSatellites() ); objMngr.registerObject( new GPSTime() ); objMngr.registerObject( new GuidanceSettings() ); objMngr.registerObject( new HomeLocation() ); + objMngr.registerObject( new HwSettings() ); objMngr.registerObject( new I2CStats() ); objMngr.registerObject( new ManualControlCommand() ); objMngr.registerObject( new ManualControlSettings() ); @@ -68,6 +75,7 @@ public class UAVObjectsInitialize { objMngr.registerObject( new PositionActual() ); objMngr.registerObject( new PositionDesired() ); objMngr.registerObject( new RateDesired() ); + objMngr.registerObject( new ReceiverActivity() ); objMngr.registerObject( new SonarAltitude() ); objMngr.registerObject( new StabilizationDesired() ); objMngr.registerObject( new StabilizationSettings() ); @@ -75,7 +83,6 @@ public class UAVObjectsInitialize { objMngr.registerObject( new SystemSettings() ); objMngr.registerObject( new SystemStats() ); objMngr.registerObject( new TaskInfo() ); - objMngr.registerObject( new TelemetrySettings() ); objMngr.registerObject( new VelocityActual() ); objMngr.registerObject( new VelocityDesired() ); objMngr.registerObject( new WatchdogStatus() ); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java index 649e6c122..97d038cfe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java @@ -136,7 +136,7 @@ public class VelocityActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0x48009C88; + protected static final int OBJID = 0x43007EB0; protected static final String NAME = "VelocityActual"; protected static String DESCRIPTION = "Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java index 27f290898..f39fbd6de 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java @@ -136,7 +136,7 @@ public class VelocityDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x122F5E3A; + protected static final int OBJID = 0x25139D1A; protected static final String NAME = "VelocityDesired"; protected static String DESCRIPTION = "Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates)."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java index 3adcad96b..acbdb43d1 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java @@ -132,7 +132,7 @@ public class WatchdogStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD646E910; + protected static final int OBJID = 0xA207FA7C; protected static final String NAME = "WatchdogStatus"; protected static String DESCRIPTION = "For monitoring the flags in the watchdog and especially the bootup flags"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index e942b238f..dc593fd5f 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -258,7 +258,7 @@ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) outCode.replace(QString("$(INITFIELDS)"), initfields); // Write the java code - bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/" + info->namelc + ".java", outCode ); + bool res = writeFileIfDiffrent( javaOutputPath.absolutePath() + "/" + info->name + ".java", outCode ); if (!res) { cout << "Error: Could not write gcs output files" << endl; return false; From 92764ebc67b4240928dfeef5682442bb534c2ca6 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 5 Apr 2012 23:35:04 -0500 Subject: [PATCH 243/543] Small upgrades to teh android install --- androidgcs/.classpath | 1 + androidgcs/proguard.cfg | 2 +- androidgcs/res/layout/gcs_home.xml | 50 ++++++++---- .../androidgcs/OPTelemetryService.java | 79 ++++++++++++++++++- 4 files changed, 114 insertions(+), 18 deletions(-) diff --git a/androidgcs/.classpath b/androidgcs/.classpath index eb33e4360..c88f96260 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -5,5 +5,6 @@ + diff --git a/androidgcs/proguard.cfg b/androidgcs/proguard.cfg index 12dd0392c..ec78e7622 100644 --- a/androidgcs/proguard.cfg +++ b/androidgcs/proguard.cfg @@ -14,7 +14,7 @@ -keep public class * extends android.preference.Preference -keep public class com.android.vending.licensing.ILicensingService --keepclasseswithmembernames class * { +-keepclasseswithmembers class * { native ; } diff --git a/androidgcs/res/layout/gcs_home.xml b/androidgcs/res/layout/gcs_home.xml index e07f5b003..0ff427bcd 100644 --- a/androidgcs/res/layout/gcs_home.xml +++ b/androidgcs/res/layout/gcs_home.xml @@ -1,15 +1,37 @@ - - - - + + + + + + + \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index ce90f5a48..bc711560d 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -71,21 +71,25 @@ public class OPTelemetryService extends Service { stopSelf(msg.arg2); break; case MSG_CONNECT: - Toast.makeText(getApplicationContext(), "Attempting connection", Toast.LENGTH_SHORT).show(); terminate = false; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); - //int connection_type = Integer.decode(prefs.getString("connection_type", "")); - int connection_type = 1; + int connection_type = Integer.decode(prefs.getString("connection_type", "")); switch(connection_type) { case 0: // No connection return; case 1: + Toast.makeText(getApplicationContext(), "Attempting fake connection", Toast.LENGTH_SHORT).show(); activeTelem = new FakeTelemetryThread(); break; case 2: + Toast.makeText(getApplicationContext(), "Attempting BT connection", Toast.LENGTH_SHORT).show(); activeTelem = new BTTelemetryThread(); break; case 3: + Toast.makeText(getApplicationContext(), "Attempting TCP connection", Toast.LENGTH_SHORT).show(); + activeTelem = new TcpTelemetryThread(); + break; + default: throw new Error("Unsupported"); } activeTelem.start(); @@ -329,6 +333,75 @@ public class OPTelemetryService extends Service { }; + private class TcpTelemetryThread extends Thread implements TelemTask { + + private UAVObjectManager objMngr; + private UAVTalk uavTalk; + private Telemetry tel; + private TelemetryMonitor mon; + + public UAVObjectManager getObjectManager() { return objMngr; }; + + TcpTelemetryThread() { + objMngr = new UAVObjectManager(); + UAVObjectsInitialize.register(objMngr); + } + + public void run() { + if (DEBUG) Log.d(TAG, "Telemetry Thread started"); + + Looper.prepare(); + + TcpUAVTalk tcp = new TcpUAVTalk(OPTelemetryService.this); + for( int i = 0; i < 10; i++ ) { + if (DEBUG) Log.d(TAG, "Attempting network Connection"); + + tcp.connect(objMngr); + + if (DEBUG) Log.d(TAG, "Done attempting connection"); + if( tcp.getConnected() ) + break; + + try { + Thread.sleep(1000); + } catch (InterruptedException e) { + Log.e(TAG, "Thread interrupted while trying to connect"); + e.printStackTrace(); + return; + } + } + if( ! tcp.getConnected() ) { + return; + } + + + if (DEBUG) Log.d(TAG, "Connected via network"); + + uavTalk = tcp.getUavtalk(); + tel = new Telemetry(uavTalk, objMngr); + mon = new TelemetryMonitor(objMngr,tel); + mon.addObserver(new Observer() { + public void update(Observable arg0, Object arg1) { + System.out.println("Mon updated. Connected: " + mon.getConnected() + " objects updated: " + mon.getObjectsUpdated()); + if(mon.getConnected() /*&& mon.getObjectsUpdated()*/) { + Intent intent = new Intent(); + intent.setAction(INTENT_ACTION_CONNECTED); + sendBroadcast(intent,null); + } + } + }); + + + if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); + while( !terminate ) { + if( !uavTalk.processInputStream() ) + break; + } + if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); + } + + }; + void postNotification(int id, String message) { String ns = Context.NOTIFICATION_SERVICE; NotificationManager mNManager = (NotificationManager) getSystemService(ns); From c1c12ed57e1356e5f16a3452389d89fdcfa91746 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 10:22:38 -0500 Subject: [PATCH 244/543] Add TCP UAVTalk interface for android --- .../org/openpilot/androidgcs/TcpUAVTalk.java | 84 +++++++++++++++++++ 1 file changed, 84 insertions(+) create mode 100644 androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java diff --git a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java new file mode 100644 index 000000000..ad503757e --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java @@ -0,0 +1,84 @@ +package org.openpilot.androidgcs; + +import java.io.IOException; +import java.net.InetAddress; +import java.net.Socket; +import java.net.UnknownHostException; +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVTalk; + +import android.content.Context; +import android.util.Log; + +public class TcpUAVTalk { + private final String TAG = "TcpUAVTalk"; + public static int LOGLEVEL = 2; + public static boolean WARN = LOGLEVEL > 1; + public static boolean DEBUG = LOGLEVEL > 0; + + // Temporarily define fixed device name + public final static String IP_ADDRESS = "127.0.0.1"; + public final static int PORT = 9001; + + private UAVTalk uavTalk; + private boolean connected; + + public TcpUAVTalk(Context caller) { + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + IP_ADDRESS); + + connected = false; + } + + public boolean connect(UAVObjectManager objMngr) { + if( getConnected() ) + return true; + if( !openTelemetryTcp(objMngr) ) + return false; + return true; + } + + public boolean getConnected() { + return connected; + } + + public UAVTalk getUavtalk() { + return uavTalk; + } + + + private boolean openTelemetryTcp(UAVObjectManager objMngr) { + Log.d(TAG, "Opening conncetion to " + IP_ADDRESS); + + InetAddress serverAddr = null; + try { + serverAddr = InetAddress.getByName(IP_ADDRESS); + } catch (UnknownHostException e1) { + // TODO Auto-generated catch block + e1.printStackTrace(); + return false; + } + + Socket socket = null; + try { + socket = new Socket(serverAddr,PORT); + } catch (IOException e1) { + // TODO Auto-generated catch block + e1.printStackTrace(); + return false; + } + + connected = true; + + try { + uavTalk = new UAVTalk(socket.getInputStream(), socket.getOutputStream(), objMngr); + } catch (IOException e) { + Log.e(TAG,"Error starting UAVTalk"); + // TODO Auto-generated catch block + //e.printStackTrace(); + return false; + } + + return true; + } + +} From 9d7c15fb7f625dd928e4a7b4fd1ea040436983cd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 11:59:50 -0500 Subject: [PATCH 245/543] Enable some debugging statements --- .../org/openpilot/androidgcs/TcpUAVTalk.java | 4 ++-- .../src/org/openpilot/uavtalk/Telemetry.java | 2 +- .../openpilot/uavtalk/TelemetryMonitor.java | 3 ++- .../src/org/openpilot/uavtalk/UAVTalk.java | 18 +++++++++++------- 4 files changed, 16 insertions(+), 11 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java index ad503757e..47074f968 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java @@ -17,7 +17,7 @@ public class TcpUAVTalk { public static boolean DEBUG = LOGLEVEL > 0; // Temporarily define fixed device name - public final static String IP_ADDRESS = "127.0.0.1"; + public final static String IP_ADDRESS = "10.21.18.120"; public final static int PORT = 9001; private UAVTalk uavTalk; @@ -47,7 +47,7 @@ public class TcpUAVTalk { private boolean openTelemetryTcp(UAVObjectManager objMngr) { - Log.d(TAG, "Opening conncetion to " + IP_ADDRESS); + Log.d(TAG, "Opening conncetion to " + IP_ADDRESS + " at address " + PORT); InetAddress serverAddr = null; try { diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 1395a5c08..11e6cb2ca 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -17,7 +17,7 @@ import android.util.Log; public class Telemetry { private final String TAG = "Telemetry"; - public static int LOGLEVEL = 0; + public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index daedcc85b..903b6b29f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -185,7 +185,8 @@ public class TelemetryMonitor extends Observable{ // Force update if not yet connected gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); flightStatsObj = objMngr.getObject("FlightTelemetryStats"); - + if (DEBUG) Log.d(TAG,"GCS Status: " + gcsStatsObj.getField("Status").getValue()); + if (DEBUG) Log.d(TAG,"Flight Status: " + flightStatsObj.getField("Status").getValue()); if ( ((String) gcsStatsObj.getField("Status").getValue()).compareTo("Connected") != 0 || ((String) flightStatsObj.getField("Status").getValue()).compareTo("Connected") == 0 ) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 39c1f6ee7..5a3a9a1a5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -12,7 +12,7 @@ import android.util.Log; public class UAVTalk extends Observable { static final String TAG = "UAVTalk"; - public static int LOGLEVEL = 0; + public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -433,6 +433,7 @@ public class UAVTalk extends Observable { rxCSPacket = rxbyte; if (rxCS != rxCSPacket) { // packet error - faulty CRC + if (DEBUG) Log.d(TAG,"Bad crc"); stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -441,11 +442,14 @@ public class UAVTalk extends Observable { if (rxPacketLength != (packetSize + 1)) { // packet error - // mismatched packet // size + if (DEBUG) Log.d(TAG,"Bad size"); stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; } + if (DEBUG) Log.d(TAG,"Received"); + rxBuffer.position(0); receiveObject(rxType, rxObjId, rxInstId, rxBuffer); stats.rxObjectBytes += rxLength; @@ -500,8 +504,8 @@ public class UAVTalk extends Observable { case TYPE_OBJ_ACK: // All instances, not allowed for OBJ_ACK messages if (!allInstances) { - // System.out.println("Received object ack: " + objId + " " + - // objMngr.getObject(objId).getName()); + System.out.println("Received object ack: " + objId + " " + + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK @@ -517,8 +521,8 @@ public class UAVTalk extends Observable { case TYPE_OBJ_REQ: // Get object, if all instances are requested get instance 0 of the // object - // System.out.println("Received object request: " + objId + " " + - // objMngr.getObject(objId).getName()); + System.out.println("Received object request: " + objId + " " + + objMngr.getObject(objId).getName()); if (allInstances) { obj = objMngr.getObject(objId); } else { @@ -534,8 +538,8 @@ public class UAVTalk extends Observable { case TYPE_ACK: // All instances, not allowed for ACK messages if (!allInstances) { - // System.out.println("Received ack: " + objId + " " + - // objMngr.getObject(objId).getName()); + System.out.println("Received ack: " + objId + " " + + objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending From 097ae637bfa8f2dfe0fd64613c8ba9a6d2cf7eff Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 12:06:36 -0500 Subject: [PATCH 246/543] Remove the TCHAIN_PREFIX flag from the OSX Makefile. No clue how that got merged in. --- flight/Revolution/Makefile.osx | 3 --- 1 file changed, 3 deletions(-) diff --git a/flight/Revolution/Makefile.osx b/flight/Revolution/Makefile.osx index e2c8ea694..a38bced0d 100644 --- a/flight/Revolution/Makefile.osx +++ b/flight/Revolution/Makefile.osx @@ -40,9 +40,6 @@ USE_BOOTLOADER ?= NO # Set to YES when using Code Sourcery toolchain CODE_SOURCERY ?= NO -# Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe) -TCHAIN_PREFIX ?= /usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- - # Remove command is different for Code Sourcery on Windows REMOVE_CMD ?= rm From 2257bc59531981d37b2330da7b0168e153fef62a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 14:42:19 -0500 Subject: [PATCH 247/543] Fix an insidious bug in the Android UAVObjectField unpack method for enums that was exposed by shuffling field orders. There goes 5 hours, FML. --- androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 78ad70630..286859e63 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -226,9 +226,9 @@ public class UAVObjectField { } case ENUM: { - List l = (List) data; + List l = (List) this.data; for (int index = 0 ; index < numElements; ++index) { - l.set(index, dataIn.get(index)); + l.set(index, dataIn.get()); } break; } From 902dbd9269799022bd59ca54f29a4507f9773a65 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 14:49:57 -0500 Subject: [PATCH 248/543] Update objects and delete old UAVObjects --- .../uavtalk/uavobjects/AHRSCalibration.java | 252 ------------------ .../uavtalk/uavobjects/AHRSSettings.java | 178 ------------- .../uavtalk/uavobjects/AhrsStatus.java | 201 -------------- .../uavtalk/uavobjects/AttitudeRaw.java | 158 ----------- .../uavtalk/uavobjects/FlightStatus.java | 4 +- .../uavtalk/uavobjects/GuidanceSettings.java | 8 +- .../uavtalk/uavobjects/HomeLocation.java | 32 +-- .../uavtalk/uavobjects/HwSettings.java | 98 +++++-- .../uavobjects/ManualControlSettings.java | 4 +- .../uavtalk/uavobjects/MixerStatus.java | 10 +- .../uavtalk/uavobjects/NedAccel.java | 6 +- .../uavtalk/uavobjects/PositionActual.java | 8 +- .../uavtalk/uavobjects/PositionDesired.java | 8 +- .../uavtalk/uavobjects/SystemAlarms.java | 4 +- .../uavtalk/uavobjects/SystemStats.java | 14 +- .../uavtalk/uavobjects/TaskInfo.java | 17 +- .../uavobjects/UAVObjectsInitialize.java | 18 +- .../uavtalk/uavobjects/VelocityActual.java | 8 +- .../uavtalk/uavobjects/VelocityDesired.java | 8 +- 19 files changed, 153 insertions(+), 883 deletions(-) delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java deleted file mode 100644 index 47d42991e..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSCalibration.java +++ /dev/null @@ -1,252 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Contains the calibration settings for the @ref AHRSCommsModule - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Contains the calibration settings for the @ref AHRSCommsModule - -generated from ahrscalibration.xml - **/ -public class AHRSCalibration extends UAVDataObject { - - public AHRSCalibration() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List accel_biasElemNames = new ArrayList(); - accel_biasElemNames.add("X"); - accel_biasElemNames.add("Y"); - accel_biasElemNames.add("Z"); - fields.add( new UAVObjectField("accel_bias", "m/s", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); - - List accel_scaleElemNames = new ArrayList(); - accel_scaleElemNames.add("X"); - accel_scaleElemNames.add("Y"); - accel_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("accel_scale", "(m/s)/lsb", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); - - List accel_orthoElemNames = new ArrayList(); - accel_orthoElemNames.add("XY"); - accel_orthoElemNames.add("XZ"); - accel_orthoElemNames.add("YZ"); - fields.add( new UAVObjectField("accel_ortho", "scale", UAVObjectField.FieldType.FLOAT32, accel_orthoElemNames, null) ); - - List accel_varElemNames = new ArrayList(); - accel_varElemNames.add("X"); - accel_varElemNames.add("Y"); - accel_varElemNames.add("Z"); - fields.add( new UAVObjectField("accel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); - - List gyro_biasElemNames = new ArrayList(); - gyro_biasElemNames.add("X"); - gyro_biasElemNames.add("Y"); - gyro_biasElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_bias", "rad/s", UAVObjectField.FieldType.FLOAT32, gyro_biasElemNames, null) ); - - List gyro_scaleElemNames = new ArrayList(); - gyro_scaleElemNames.add("X"); - gyro_scaleElemNames.add("Y"); - gyro_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_scale", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, gyro_scaleElemNames, null) ); - - List gyro_varElemNames = new ArrayList(); - gyro_varElemNames.add("X"); - gyro_varElemNames.add("Y"); - gyro_varElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_var", "(rad/s)^2", UAVObjectField.FieldType.FLOAT32, gyro_varElemNames, null) ); - - List gyro_tempcompfactorElemNames = new ArrayList(); - gyro_tempcompfactorElemNames.add("X"); - gyro_tempcompfactorElemNames.add("Y"); - gyro_tempcompfactorElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_tempcompfactor", "raw/raw", UAVObjectField.FieldType.FLOAT32, gyro_tempcompfactorElemNames, null) ); - - List mag_biasElemNames = new ArrayList(); - mag_biasElemNames.add("X"); - mag_biasElemNames.add("Y"); - mag_biasElemNames.add("Z"); - fields.add( new UAVObjectField("mag_bias", "mGau", UAVObjectField.FieldType.FLOAT32, mag_biasElemNames, null) ); - - List mag_scaleElemNames = new ArrayList(); - mag_scaleElemNames.add("X"); - mag_scaleElemNames.add("Y"); - mag_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("mag_scale", "(mGau)/lsb", UAVObjectField.FieldType.FLOAT32, mag_scaleElemNames, null) ); - - List mag_varElemNames = new ArrayList(); - mag_varElemNames.add("X"); - mag_varElemNames.add("Y"); - mag_varElemNames.add("Z"); - fields.add( new UAVObjectField("mag_var", "mGau^2", UAVObjectField.FieldType.FLOAT32, mag_varElemNames, null) ); - - List vel_varElemNames = new ArrayList(); - vel_varElemNames.add("0"); - fields.add( new UAVObjectField("vel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, vel_varElemNames, null) ); - - List pos_varElemNames = new ArrayList(); - pos_varElemNames.add("0"); - fields.add( new UAVObjectField("pos_var", "m^2", UAVObjectField.FieldType.FLOAT32, pos_varElemNames, null) ); - - List measure_varElemNames = new ArrayList(); - measure_varElemNames.add("0"); - List measure_varEnumOptions = new ArrayList(); - measure_varEnumOptions.add("SET"); - measure_varEnumOptions.add("MEASURE"); - fields.add( new UAVObjectField("measure_var", "", UAVObjectField.FieldType.ENUM, measure_varElemNames, measure_varEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("accel_bias").setValue(-73.5,0); - getField("accel_bias").setValue(-73.5,1); - getField("accel_bias").setValue(73.5,2); - getField("accel_scale").setValue(0.0359,0); - getField("accel_scale").setValue(0.0359,1); - getField("accel_scale").setValue(0.0359,2); - getField("accel_ortho").setValue(0,0); - getField("accel_ortho").setValue(0,1); - getField("accel_ortho").setValue(0,2); - getField("accel_var").setValue(0.0005,0); - getField("accel_var").setValue(0.0005,1); - getField("accel_var").setValue(0.0005,2); - getField("gyro_bias").setValue(28,0); - getField("gyro_bias").setValue(-28,1); - getField("gyro_bias").setValue(28,2); - getField("gyro_scale").setValue(-0.017,0); - getField("gyro_scale").setValue(0.017,1); - getField("gyro_scale").setValue(-0.017,2); - getField("gyro_var").setValue(0.0001,0); - getField("gyro_var").setValue(0.0001,1); - getField("gyro_var").setValue(0.0001,2); - getField("gyro_tempcompfactor").setValue(0,0); - getField("gyro_tempcompfactor").setValue(0,1); - getField("gyro_tempcompfactor").setValue(0,2); - getField("mag_bias").setValue(0,0); - getField("mag_bias").setValue(0,1); - getField("mag_bias").setValue(0,2); - getField("mag_scale").setValue(1,0); - getField("mag_scale").setValue(1,1); - getField("mag_scale").setValue(1,2); - getField("mag_var").setValue(50,0); - getField("mag_var").setValue(50,1); - getField("mag_var").setValue(50,2); - getField("vel_var").setValue(10); - getField("pos_var").setValue(0.04); - getField("measure_var").setValue("SET"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - AHRSCalibration obj = new AHRSCalibration(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AHRSCalibration GetInstance(UAVObjectManager objMngr, int instID) - { - return (AHRSCalibration)(objMngr.getObject(AHRSCalibration.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0xFD0EDFC4; - protected static final String NAME = "AHRSCalibration"; - protected static String DESCRIPTION = "Contains the calibration settings for the @ref AHRSCommsModule"; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 1 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java deleted file mode 100644 index 032dae775..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AHRSSettings.java +++ /dev/null @@ -1,178 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref AHRSCommsModule to control the algorithm and what is updated - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref AHRSCommsModule to control the algorithm and what is updated - -generated from ahrssettings.xml - **/ -public class AHRSSettings extends UAVDataObject { - - public AHRSSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List YawBiasElemNames = new ArrayList(); - YawBiasElemNames.add("0"); - fields.add( new UAVObjectField("YawBias", "", UAVObjectField.FieldType.FLOAT32, YawBiasElemNames, null) ); - - List PitchBiasElemNames = new ArrayList(); - PitchBiasElemNames.add("0"); - fields.add( new UAVObjectField("PitchBias", "", UAVObjectField.FieldType.FLOAT32, PitchBiasElemNames, null) ); - - List RollBiasElemNames = new ArrayList(); - RollBiasElemNames.add("0"); - fields.add( new UAVObjectField("RollBias", "", UAVObjectField.FieldType.FLOAT32, RollBiasElemNames, null) ); - - List AlgorithmElemNames = new ArrayList(); - AlgorithmElemNames.add("0"); - List AlgorithmEnumOptions = new ArrayList(); - AlgorithmEnumOptions.add("SIMPLE"); - AlgorithmEnumOptions.add("INSGPS_INDOOR_NOMAG"); - AlgorithmEnumOptions.add("INSGPS_INDOOR"); - AlgorithmEnumOptions.add("INSGPS_OUTDOOR"); - fields.add( new UAVObjectField("Algorithm", "", UAVObjectField.FieldType.ENUM, AlgorithmElemNames, AlgorithmEnumOptions) ); - - List DownsamplingElemNames = new ArrayList(); - DownsamplingElemNames.add("0"); - fields.add( new UAVObjectField("Downsampling", "", UAVObjectField.FieldType.UINT8, DownsamplingElemNames, null) ); - - List UpdatePeriodElemNames = new ArrayList(); - UpdatePeriodElemNames.add("0"); - fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.UINT8, UpdatePeriodElemNames, null) ); - - List BiasCorrectedRawElemNames = new ArrayList(); - BiasCorrectedRawElemNames.add("0"); - List BiasCorrectedRawEnumOptions = new ArrayList(); - BiasCorrectedRawEnumOptions.add("TRUE"); - BiasCorrectedRawEnumOptions.add("FALSE"); - fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("YawBias").setValue(0); - getField("PitchBias").setValue(0); - getField("RollBias").setValue(0); - getField("Algorithm").setValue("INSGPS_INDOOR_NOMAG"); - getField("Downsampling").setValue(20); - getField("UpdatePeriod").setValue(1); - getField("BiasCorrectedRaw").setValue("TRUE"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - AHRSSettings obj = new AHRSSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AHRSSettings GetInstance(UAVObjectManager objMngr, int instID) - { - return (AHRSSettings)(objMngr.getObject(AHRSSettings.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0xF8591ED8; - protected static final String NAME = "AHRSSettings"; - protected static String DESCRIPTION = "Settings for the @ref AHRSCommsModule to control the algorithm and what is updated"; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 1 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java deleted file mode 100644 index 82e447a70..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AhrsStatus.java +++ /dev/null @@ -1,201 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Status for the @ref AHRSCommsModule, including communication errors - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Status for the @ref AHRSCommsModule, including communication errors - -generated from ahrsstatus.xml - **/ -public class AhrsStatus extends UAVDataObject { - - public AhrsStatus() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List RunningTimeElemNames = new ArrayList(); - RunningTimeElemNames.add("0"); - fields.add( new UAVObjectField("RunningTime", "ms", UAVObjectField.FieldType.UINT32, RunningTimeElemNames, null) ); - - List SerialNumberElemNames = new ArrayList(); - SerialNumberElemNames.add("0"); - SerialNumberElemNames.add("1"); - SerialNumberElemNames.add("2"); - SerialNumberElemNames.add("3"); - SerialNumberElemNames.add("4"); - SerialNumberElemNames.add("5"); - SerialNumberElemNames.add("6"); - SerialNumberElemNames.add("7"); - fields.add( new UAVObjectField("SerialNumber", "", UAVObjectField.FieldType.UINT8, SerialNumberElemNames, null) ); - - List CPULoadElemNames = new ArrayList(); - CPULoadElemNames.add("0"); - fields.add( new UAVObjectField("CPULoad", "count", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); - - List IdleTimePerCyleElemNames = new ArrayList(); - IdleTimePerCyleElemNames.add("0"); - fields.add( new UAVObjectField("IdleTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, IdleTimePerCyleElemNames, null) ); - - List RunningTimePerCyleElemNames = new ArrayList(); - RunningTimePerCyleElemNames.add("0"); - fields.add( new UAVObjectField("RunningTimePerCyle", "10x ms", UAVObjectField.FieldType.UINT8, RunningTimePerCyleElemNames, null) ); - - List DroppedUpdatesElemNames = new ArrayList(); - DroppedUpdatesElemNames.add("0"); - fields.add( new UAVObjectField("DroppedUpdates", "count", UAVObjectField.FieldType.UINT8, DroppedUpdatesElemNames, null) ); - - List LinkRunningElemNames = new ArrayList(); - LinkRunningElemNames.add("0"); - List LinkRunningEnumOptions = new ArrayList(); - LinkRunningEnumOptions.add("FALSE"); - LinkRunningEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("LinkRunning", "", UAVObjectField.FieldType.ENUM, LinkRunningElemNames, LinkRunningEnumOptions) ); - - List AhrsKickstartsElemNames = new ArrayList(); - AhrsKickstartsElemNames.add("0"); - fields.add( new UAVObjectField("AhrsKickstarts", "count", UAVObjectField.FieldType.UINT8, AhrsKickstartsElemNames, null) ); - - List AhrsCrcErrorsElemNames = new ArrayList(); - AhrsCrcErrorsElemNames.add("0"); - fields.add( new UAVObjectField("AhrsCrcErrors", "count", UAVObjectField.FieldType.UINT8, AhrsCrcErrorsElemNames, null) ); - - List AhrsRetriesElemNames = new ArrayList(); - AhrsRetriesElemNames.add("0"); - fields.add( new UAVObjectField("AhrsRetries", "count", UAVObjectField.FieldType.UINT8, AhrsRetriesElemNames, null) ); - - List AhrsInvalidPacketsElemNames = new ArrayList(); - AhrsInvalidPacketsElemNames.add("0"); - fields.add( new UAVObjectField("AhrsInvalidPackets", "count", UAVObjectField.FieldType.UINT8, AhrsInvalidPacketsElemNames, null) ); - - List OpCrcErrorsElemNames = new ArrayList(); - OpCrcErrorsElemNames.add("0"); - fields.add( new UAVObjectField("OpCrcErrors", "count", UAVObjectField.FieldType.UINT8, OpCrcErrorsElemNames, null) ); - - List OpRetriesElemNames = new ArrayList(); - OpRetriesElemNames.add("0"); - fields.add( new UAVObjectField("OpRetries", "count", UAVObjectField.FieldType.UINT8, OpRetriesElemNames, null) ); - - List OpInvalidPacketsElemNames = new ArrayList(); - OpInvalidPacketsElemNames.add("0"); - fields.add( new UAVObjectField("OpInvalidPackets", "count", UAVObjectField.FieldType.UINT8, OpInvalidPacketsElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - AhrsStatus obj = new AhrsStatus(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AhrsStatus GetInstance(UAVObjectManager objMngr, int instID) - { - return (AhrsStatus)(objMngr.getObject(AhrsStatus.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0x706D1AB8; - protected static final String NAME = "AhrsStatus"; - protected static String DESCRIPTION = "Status for the @ref AHRSCommsModule, including communication errors"; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 0 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java deleted file mode 100644 index b8c3aacb4..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeRaw.java +++ /dev/null @@ -1,158 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The raw attitude sensor data from @ref AHRSCommsModule. Not always updated. - -generated from attituderaw.xml - **/ -public class AttitudeRaw extends UAVDataObject { - - public AttitudeRaw() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List gyrosElemNames = new ArrayList(); - gyrosElemNames.add("X"); - gyrosElemNames.add("Y"); - gyrosElemNames.add("Z"); - fields.add( new UAVObjectField("gyros", "deg/s", UAVObjectField.FieldType.FLOAT32, gyrosElemNames, null) ); - - List accelsElemNames = new ArrayList(); - accelsElemNames.add("X"); - accelsElemNames.add("Y"); - accelsElemNames.add("Z"); - fields.add( new UAVObjectField("accels", "m/s^2", UAVObjectField.FieldType.FLOAT32, accelsElemNames, null) ); - - List magnetometersElemNames = new ArrayList(); - magnetometersElemNames.add("X"); - magnetometersElemNames.add("Y"); - magnetometersElemNames.add("Z"); - fields.add( new UAVObjectField("magnetometers", "mGa", UAVObjectField.FieldType.INT16, magnetometersElemNames, null) ); - - List gyrotempElemNames = new ArrayList(); - gyrotempElemNames.add("XY"); - gyrotempElemNames.add("Z"); - fields.add( new UAVObjectField("gyrotemp", "raw", UAVObjectField.FieldType.UINT16, gyrotempElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - AttitudeRaw obj = new AttitudeRaw(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AttitudeRaw GetInstance(UAVObjectManager objMngr, int instID) - { - return (AttitudeRaw)(objMngr.getObject(AttitudeRaw.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0xDB722974; - protected static final String NAME = "AttitudeRaw"; - protected static String DESCRIPTION = "The raw attitude sensor data from @ref AHRSCommsModule. Not always updated."; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 0 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java index d775b21e7..ac3812aa6 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java @@ -66,8 +66,10 @@ public class FlightStatus extends UAVDataObject { FlightModeEnumOptions.add("Stabilized1"); FlightModeEnumOptions.add("Stabilized2"); FlightModeEnumOptions.add("Stabilized3"); + FlightModeEnumOptions.add("AltitudeHold"); FlightModeEnumOptions.add("VelocityControl"); FlightModeEnumOptions.add("PositionHold"); + FlightModeEnumOptions.add("PathPlanner"); fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); @@ -144,7 +146,7 @@ public class FlightStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x743DB13C; + protected static final int OBJID = 0x19B92D8; protected static final String NAME = "FlightStatus"; protected static String DESCRIPTION = "Contains major flight status information for other modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java index 205384efe..5510a901d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java @@ -55,14 +55,14 @@ public class GuidanceSettings extends UAVDataObject { HorizontalPosPIElemNames.add("Kp"); HorizontalPosPIElemNames.add("Ki"); HorizontalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalPosPI", "(cm/s)/cm", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); + fields.add( new UAVObjectField("HorizontalPosPI", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); List HorizontalVelPIDElemNames = new ArrayList(); HorizontalVelPIDElemNames.add("Kp"); HorizontalVelPIDElemNames.add("Ki"); HorizontalVelPIDElemNames.add("Kd"); HorizontalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalVelPID", "deg/(cm/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); + fields.add( new UAVObjectField("HorizontalVelPID", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); List VerticalPosPIElemNames = new ArrayList(); VerticalPosPIElemNames.add("Kp"); @@ -87,11 +87,11 @@ public class GuidanceSettings extends UAVDataObject { List HorizontalVelMaxElemNames = new ArrayList(); HorizontalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("HorizontalVelMax", "cm/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); + fields.add( new UAVObjectField("HorizontalVelMax", "m/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); List VerticalVelMaxElemNames = new ArrayList(); VerticalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("VerticalVelMax", "cm/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); + fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); List GuidanceModeElemNames = new ArrayList(); GuidanceModeElemNames.add("0"); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java index 68abb3633..3f3b3d8dd 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -63,24 +63,6 @@ public class HomeLocation extends UAVDataObject { AltitudeElemNames.add("0"); fields.add( new UAVObjectField("Altitude", "m over geoid", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); - List ECEFElemNames = new ArrayList(); - ECEFElemNames.add("0"); - ECEFElemNames.add("1"); - ECEFElemNames.add("2"); - fields.add( new UAVObjectField("ECEF", "cm", UAVObjectField.FieldType.INT32, ECEFElemNames, null) ); - - List RNEElemNames = new ArrayList(); - RNEElemNames.add("0"); - RNEElemNames.add("1"); - RNEElemNames.add("2"); - RNEElemNames.add("3"); - RNEElemNames.add("4"); - RNEElemNames.add("5"); - RNEElemNames.add("6"); - RNEElemNames.add("7"); - RNEElemNames.add("8"); - fields.add( new UAVObjectField("RNE", "", UAVObjectField.FieldType.FLOAT32, RNEElemNames, null) ); - List BeElemNames = new ArrayList(); BeElemNames.add("0"); BeElemNames.add("1"); @@ -146,18 +128,6 @@ public class HomeLocation extends UAVDataObject { getField("Latitude").setValue(0); getField("Longitude").setValue(0); getField("Altitude").setValue(0); - getField("ECEF").setValue(0,0); - getField("ECEF").setValue(0,1); - getField("ECEF").setValue(0,2); - getField("RNE").setValue(0,0); - getField("RNE").setValue(0,1); - getField("RNE").setValue(0,2); - getField("RNE").setValue(0,3); - getField("RNE").setValue(0,4); - getField("RNE").setValue(0,5); - getField("RNE").setValue(0,6); - getField("RNE").setValue(0,7); - getField("RNE").setValue(0,8); getField("Be").setValue(0,0); getField("Be").setValue(0,1); getField("Be").setValue(0,2); @@ -191,7 +161,7 @@ public class HomeLocation extends UAVDataObject { } // Constants - protected static final int OBJID = 0x5BB3AEFC; + protected static final int OBJID = 0x6185DC6E; protected static final String NAME = "HomeLocation"; protected static String DESCRIPTION = "HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java index 83b7ae7b6..f56982e69 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java @@ -89,31 +89,70 @@ public class HwSettings extends UAVDataObject { CC_FlexiPortEnumOptions.add("ComBridge"); fields.add( new UAVObjectField("CC_FlexiPort", "function", UAVObjectField.FieldType.ENUM, CC_FlexiPortElemNames, CC_FlexiPortEnumOptions) ); - List OP_RcvrPortElemNames = new ArrayList(); - OP_RcvrPortElemNames.add("0"); - List OP_RcvrPortEnumOptions = new ArrayList(); - OP_RcvrPortEnumOptions.add("Disabled"); - OP_RcvrPortEnumOptions.add("PWM"); - OP_RcvrPortEnumOptions.add("PPM"); - OP_RcvrPortEnumOptions.add("DSM2"); - OP_RcvrPortEnumOptions.add("DSMX (10bit)"); - OP_RcvrPortEnumOptions.add("DSMX (11bit)"); - OP_RcvrPortEnumOptions.add("Debug"); - fields.add( new UAVObjectField("OP_RcvrPort", "function", UAVObjectField.FieldType.ENUM, OP_RcvrPortElemNames, OP_RcvrPortEnumOptions) ); + List RV_RcvrPortElemNames = new ArrayList(); + RV_RcvrPortElemNames.add("0"); + List RV_RcvrPortEnumOptions = new ArrayList(); + RV_RcvrPortEnumOptions.add("Disabled"); + RV_RcvrPortEnumOptions.add("PWM"); + RV_RcvrPortEnumOptions.add("PPM"); + RV_RcvrPortEnumOptions.add("PPM+Outputs"); + RV_RcvrPortEnumOptions.add("Outputs"); + fields.add( new UAVObjectField("RV_RcvrPort", "function", UAVObjectField.FieldType.ENUM, RV_RcvrPortElemNames, RV_RcvrPortEnumOptions) ); - List OP_MainPortElemNames = new ArrayList(); - OP_MainPortElemNames.add("0"); - List OP_MainPortEnumOptions = new ArrayList(); - OP_MainPortEnumOptions.add("Disabled"); - OP_MainPortEnumOptions.add("Telemetry"); - fields.add( new UAVObjectField("OP_MainPort", "function", UAVObjectField.FieldType.ENUM, OP_MainPortElemNames, OP_MainPortEnumOptions) ); + List RV_AuxPortElemNames = new ArrayList(); + RV_AuxPortElemNames.add("0"); + List RV_AuxPortEnumOptions = new ArrayList(); + RV_AuxPortEnumOptions.add("Disabled"); + RV_AuxPortEnumOptions.add("Telemetry"); + RV_AuxPortEnumOptions.add("DSM2"); + RV_AuxPortEnumOptions.add("DSMX (10bit)"); + RV_AuxPortEnumOptions.add("DSMX (11bit)"); + RV_AuxPortEnumOptions.add("ComAux"); + RV_AuxPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_AuxPort", "function", UAVObjectField.FieldType.ENUM, RV_AuxPortElemNames, RV_AuxPortEnumOptions) ); - List OP_FlexiPortElemNames = new ArrayList(); - OP_FlexiPortElemNames.add("0"); - List OP_FlexiPortEnumOptions = new ArrayList(); - OP_FlexiPortEnumOptions.add("Disabled"); - OP_FlexiPortEnumOptions.add("GPS"); - fields.add( new UAVObjectField("OP_FlexiPort", "function", UAVObjectField.FieldType.ENUM, OP_FlexiPortElemNames, OP_FlexiPortEnumOptions) ); + List RV_AuxSBusPortElemNames = new ArrayList(); + RV_AuxSBusPortElemNames.add("0"); + List RV_AuxSBusPortEnumOptions = new ArrayList(); + RV_AuxSBusPortEnumOptions.add("Disabled"); + RV_AuxSBusPortEnumOptions.add("S.Bus"); + RV_AuxSBusPortEnumOptions.add("DSM2"); + RV_AuxSBusPortEnumOptions.add("DSMX (10bit)"); + RV_AuxSBusPortEnumOptions.add("DSMX (11bit)"); + RV_AuxSBusPortEnumOptions.add("ComAux"); + RV_AuxSBusPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_AuxSBusPort", "function", UAVObjectField.FieldType.ENUM, RV_AuxSBusPortElemNames, RV_AuxSBusPortEnumOptions) ); + + List RV_FlexiPortElemNames = new ArrayList(); + RV_FlexiPortElemNames.add("0"); + List RV_FlexiPortEnumOptions = new ArrayList(); + RV_FlexiPortEnumOptions.add("Disabled"); + RV_FlexiPortEnumOptions.add("I2C"); + RV_FlexiPortEnumOptions.add("DSM2"); + RV_FlexiPortEnumOptions.add("DSMX (10bit)"); + RV_FlexiPortEnumOptions.add("DSMX (11bit)"); + RV_FlexiPortEnumOptions.add("ComAux"); + RV_FlexiPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_FlexiPort", "function", UAVObjectField.FieldType.ENUM, RV_FlexiPortElemNames, RV_FlexiPortEnumOptions) ); + + List RV_TelemetryPortElemNames = new ArrayList(); + RV_TelemetryPortElemNames.add("0"); + List RV_TelemetryPortEnumOptions = new ArrayList(); + RV_TelemetryPortEnumOptions.add("Disabled"); + RV_TelemetryPortEnumOptions.add("Telemetry"); + RV_TelemetryPortEnumOptions.add("ComAux"); + RV_TelemetryPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_TelemetryPort", "function", UAVObjectField.FieldType.ENUM, RV_TelemetryPortElemNames, RV_TelemetryPortEnumOptions) ); + + List RV_GPSPortElemNames = new ArrayList(); + RV_GPSPortElemNames.add("0"); + List RV_GPSPortEnumOptions = new ArrayList(); + RV_GPSPortEnumOptions.add("Disabled"); + RV_GPSPortEnumOptions.add("Telemetry"); + RV_GPSPortEnumOptions.add("GPS"); + RV_GPSPortEnumOptions.add("ComAux"); + RV_GPSPortEnumOptions.add("ComBridge"); + fields.add( new UAVObjectField("RV_GPSPort", "function", UAVObjectField.FieldType.ENUM, RV_GPSPortElemNames, RV_GPSPortEnumOptions) ); List TelemetrySpeedElemNames = new ArrayList(); TelemetrySpeedElemNames.add("0"); @@ -180,6 +219,7 @@ public class HwSettings extends UAVDataObject { OptionalModulesElemNames.add("ComUsbBridge"); OptionalModulesElemNames.add("Fault"); OptionalModulesElemNames.add("Altitude"); + OptionalModulesElemNames.add("TxPID"); List OptionalModulesEnumOptions = new ArrayList(); OptionalModulesEnumOptions.add("Disabled"); OptionalModulesEnumOptions.add("Enabled"); @@ -237,9 +277,12 @@ public class HwSettings extends UAVDataObject { getField("CC_RcvrPort").setValue("PWM"); getField("CC_MainPort").setValue("Disabled"); getField("CC_FlexiPort").setValue("Disabled"); - getField("OP_RcvrPort").setValue("PWM"); - getField("OP_MainPort").setValue("Telemetry"); - getField("OP_FlexiPort").setValue("GPS"); + getField("RV_RcvrPort").setValue("PWM"); + getField("RV_AuxPort").setValue("Disabled"); + getField("RV_AuxSBusPort").setValue("Disabled"); + getField("RV_FlexiPort").setValue("Disabled"); + getField("RV_TelemetryPort").setValue("Telemetry"); + getField("RV_GPSPort").setValue("GPS"); getField("TelemetrySpeed").setValue("57600"); getField("GPSSpeed").setValue("57600"); getField("ComUsbBridgeSpeed").setValue("57600"); @@ -251,6 +294,7 @@ public class HwSettings extends UAVDataObject { getField("OptionalModules").setValue("Disabled",2); getField("OptionalModules").setValue("Disabled",3); getField("OptionalModules").setValue("Disabled",4); + getField("OptionalModules").setValue("Disabled",5); getField("DSMxBind").setValue(0); } @@ -280,7 +324,7 @@ public class HwSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x2EE6575A; + protected static final int OBJID = 0x4730375C; protected static final String NAME = "HwSettings"; protected static String DESCRIPTION = "Selection of optional hardware configurations."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java index bb846695d..c8f460bc4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -181,8 +181,10 @@ public class ManualControlSettings extends UAVDataObject { FlightModePositionEnumOptions.add("Stabilized1"); FlightModePositionEnumOptions.add("Stabilized2"); FlightModePositionEnumOptions.add("Stabilized3"); + FlightModePositionEnumOptions.add("AltitudeHold"); FlightModePositionEnumOptions.add("VelocityControl"); FlightModePositionEnumOptions.add("PositionHold"); + FlightModePositionEnumOptions.add("PathPlanner"); fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); @@ -317,7 +319,7 @@ public class ManualControlSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x24959BB0; + protected static final int OBJID = 0x59C4551C; protected static final String NAME = "ManualControlSettings"; protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java index 106220a8c..80e3b15bf 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java @@ -83,6 +83,14 @@ public class MixerStatus extends UAVDataObject { Mixer8ElemNames.add("0"); fields.add( new UAVObjectField("Mixer8", "", UAVObjectField.FieldType.FLOAT32, Mixer8ElemNames, null) ); + List Mixer9ElemNames = new ArrayList(); + Mixer9ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer9", "", UAVObjectField.FieldType.FLOAT32, Mixer9ElemNames, null) ); + + List Mixer10ElemNames = new ArrayList(); + Mixer10ElemNames.add("0"); + fields.add( new UAVObjectField("Mixer10", "", UAVObjectField.FieldType.FLOAT32, Mixer10ElemNames, null) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -156,7 +164,7 @@ public class MixerStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x11CFB4E6; + protected static final int OBJID = 0x124E28A; protected static final String NAME = "MixerStatus"; protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java index 3b09dd1f8..1629a19d2 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java @@ -53,15 +53,15 @@ public class NedAccel extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm/s^2", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m/s^2", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm/s^2", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m/s^2", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm/s^2", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m/s^2", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java index ac30ad4f5..184098a16 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java @@ -53,15 +53,15 @@ public class PositionActual extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object @@ -136,7 +136,7 @@ public class PositionActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF9691DA4; + protected static final int OBJID = 0xFA9E2D42; protected static final String NAME = "PositionActual"; protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java index 2ff5a5586..123ca58af 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java @@ -53,15 +53,15 @@ public class PositionDesired extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object @@ -136,7 +136,7 @@ public class PositionDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x33C9EAB4; + protected static final int OBJID = 0x778DBE24; protected static final String NAME = "PositionDesired"; protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java index 458dd9d10..bc4bf0625 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -61,6 +61,7 @@ public class SystemAlarms extends UAVDataObject { AlarmElemNames.add("ManualControl"); AlarmElemNames.add("Actuator"); AlarmElemNames.add("Attitude"); + AlarmElemNames.add("Sensors"); AlarmElemNames.add("Stabilization"); AlarmElemNames.add("Guidance"); AlarmElemNames.add("AHRSComms"); @@ -139,6 +140,7 @@ public class SystemAlarms extends UAVDataObject { getField("Alarm").setValue("Uninitialised",14); getField("Alarm").setValue("Uninitialised",15); getField("Alarm").setValue("Uninitialised",16); + getField("Alarm").setValue("Uninitialised",17); } @@ -167,7 +169,7 @@ public class SystemAlarms extends UAVDataObject { } // Constants - protected static final int OBJID = 0x737ADCF2; + protected static final int OBJID = 0x9C7CBFE; protected static final String NAME = "SystemAlarms"; protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java index d1c51d43f..26d01f2a0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java @@ -55,6 +55,18 @@ public class SystemStats extends UAVDataObject { FlightTimeElemNames.add("0"); fields.add( new UAVObjectField("FlightTime", "ms", UAVObjectField.FieldType.UINT32, FlightTimeElemNames, null) ); + List EventSystemWarningIDElemNames = new ArrayList(); + EventSystemWarningIDElemNames.add("0"); + fields.add( new UAVObjectField("EventSystemWarningID", "uavoid", UAVObjectField.FieldType.UINT32, EventSystemWarningIDElemNames, null) ); + + List ObjectManagerCallbackIDElemNames = new ArrayList(); + ObjectManagerCallbackIDElemNames.add("0"); + fields.add( new UAVObjectField("ObjectManagerCallbackID", "uavoid", UAVObjectField.FieldType.UINT32, ObjectManagerCallbackIDElemNames, null) ); + + List ObjectManagerQueueIDElemNames = new ArrayList(); + ObjectManagerQueueIDElemNames.add("0"); + fields.add( new UAVObjectField("ObjectManagerQueueID", "uavoid", UAVObjectField.FieldType.UINT32, ObjectManagerQueueIDElemNames, null) ); + List HeapRemainingElemNames = new ArrayList(); HeapRemainingElemNames.add("0"); fields.add( new UAVObjectField("HeapRemaining", "bytes", UAVObjectField.FieldType.UINT16, HeapRemainingElemNames, null) ); @@ -144,7 +156,7 @@ public class SystemStats extends UAVDataObject { } // Constants - protected static final int OBJID = 0xD610A0F0; + protected static final int OBJID = 0x364D1406; protected static final String NAME = "SystemStats"; protected static String DESCRIPTION = "CPU and memory usage from OpenPilot computer. "; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java index 54825fafe..eefcef6d9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -55,36 +55,42 @@ public class TaskInfo extends UAVDataObject { StackRemainingElemNames.add("System"); StackRemainingElemNames.add("Actuator"); StackRemainingElemNames.add("Attitude"); + StackRemainingElemNames.add("Sensors"); StackRemainingElemNames.add("TelemetryTx"); StackRemainingElemNames.add("TelemetryTxPri"); StackRemainingElemNames.add("TelemetryRx"); StackRemainingElemNames.add("GPS"); StackRemainingElemNames.add("ManualControl"); StackRemainingElemNames.add("Altitude"); - StackRemainingElemNames.add("AHRSComms"); StackRemainingElemNames.add("Stabilization"); + StackRemainingElemNames.add("AltitudeHold"); StackRemainingElemNames.add("Guidance"); StackRemainingElemNames.add("FlightPlan"); + StackRemainingElemNames.add("PathPlanner"); StackRemainingElemNames.add("Com2UsbBridge"); StackRemainingElemNames.add("Usb2ComBridge"); + StackRemainingElemNames.add("OveroSync"); fields.add( new UAVObjectField("StackRemaining", "bytes", UAVObjectField.FieldType.UINT16, StackRemainingElemNames, null) ); List RunningElemNames = new ArrayList(); RunningElemNames.add("System"); RunningElemNames.add("Actuator"); RunningElemNames.add("Attitude"); + RunningElemNames.add("Sensors"); RunningElemNames.add("TelemetryTx"); RunningElemNames.add("TelemetryTxPri"); RunningElemNames.add("TelemetryRx"); RunningElemNames.add("GPS"); RunningElemNames.add("ManualControl"); RunningElemNames.add("Altitude"); - RunningElemNames.add("AHRSComms"); RunningElemNames.add("Stabilization"); + RunningElemNames.add("AltitudeHold"); RunningElemNames.add("Guidance"); RunningElemNames.add("FlightPlan"); + RunningElemNames.add("PathPlanner"); RunningElemNames.add("Com2UsbBridge"); RunningElemNames.add("Usb2ComBridge"); + RunningElemNames.add("OveroSync"); List RunningEnumOptions = new ArrayList(); RunningEnumOptions.add("False"); RunningEnumOptions.add("True"); @@ -94,18 +100,21 @@ public class TaskInfo extends UAVDataObject { RunningTimeElemNames.add("System"); RunningTimeElemNames.add("Actuator"); RunningTimeElemNames.add("Attitude"); + RunningTimeElemNames.add("Sensors"); RunningTimeElemNames.add("TelemetryTx"); RunningTimeElemNames.add("TelemetryTxPri"); RunningTimeElemNames.add("TelemetryRx"); RunningTimeElemNames.add("GPS"); RunningTimeElemNames.add("ManualControl"); RunningTimeElemNames.add("Altitude"); - RunningTimeElemNames.add("AHRSComms"); RunningTimeElemNames.add("Stabilization"); + RunningTimeElemNames.add("AltitudeHold"); RunningTimeElemNames.add("Guidance"); RunningTimeElemNames.add("FlightPlan"); + RunningTimeElemNames.add("PathPlanner"); RunningTimeElemNames.add("Com2UsbBridge"); RunningTimeElemNames.add("Usb2ComBridge"); + RunningTimeElemNames.add("OveroSync"); fields.add( new UAVObjectField("RunningTime", "%", UAVObjectField.FieldType.UINT8, RunningTimeElemNames, null) ); @@ -181,7 +190,7 @@ public class TaskInfo extends UAVDataObject { } // Constants - protected static final int OBJID = 0xE34A7C32; + protected static final int OBJID = 0x498F54BA; protected static final String NAME = "TaskInfo"; protected static String DESCRIPTION = "Task information"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java index c2cf64d49..823643130 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -35,15 +35,15 @@ public class UAVObjectsInitialize { public static void register(UAVObjectManager objMngr) { try { + objMngr.registerObject( new Accels() ); objMngr.registerObject( new AccessoryDesired() ); objMngr.registerObject( new ActuatorCommand() ); objMngr.registerObject( new ActuatorDesired() ); objMngr.registerObject( new ActuatorSettings() ); - objMngr.registerObject( new AHRSCalibration() ); - objMngr.registerObject( new AHRSSettings() ); - objMngr.registerObject( new AhrsStatus() ); + objMngr.registerObject( new AltHoldSmoothed() ); + objMngr.registerObject( new AltitudeHoldDesired() ); + objMngr.registerObject( new AltitudeHoldSettings() ); objMngr.registerObject( new AttitudeActual() ); - objMngr.registerObject( new AttitudeRaw() ); objMngr.registerObject( new AttitudeSettings() ); objMngr.registerObject( new BaroAltitude() ); objMngr.registerObject( new CameraDesired() ); @@ -62,16 +62,23 @@ public class UAVObjectsInitialize { objMngr.registerObject( new GPSPosition() ); objMngr.registerObject( new GPSSatellites() ); objMngr.registerObject( new GPSTime() ); + objMngr.registerObject( new GPSVelocity() ); + objMngr.registerObject( new Gyros() ); + objMngr.registerObject( new GyrosBias() ); objMngr.registerObject( new GuidanceSettings() ); objMngr.registerObject( new HomeLocation() ); objMngr.registerObject( new HwSettings() ); objMngr.registerObject( new I2CStats() ); + objMngr.registerObject( new GPSPosition() ); + objMngr.registerObject( new Magnetometer() ); objMngr.registerObject( new ManualControlCommand() ); objMngr.registerObject( new ManualControlSettings() ); objMngr.registerObject( new MixerSettings() ); objMngr.registerObject( new MixerStatus() ); + objMngr.registerObject( new NEDPosition() ); objMngr.registerObject( new NedAccel() ); objMngr.registerObject( new ObjectPersistence() ); + objMngr.registerObject( new PathDesired() ); objMngr.registerObject( new PositionActual() ); objMngr.registerObject( new PositionDesired() ); objMngr.registerObject( new RateDesired() ); @@ -82,10 +89,13 @@ public class UAVObjectsInitialize { objMngr.registerObject( new SystemAlarms() ); objMngr.registerObject( new SystemSettings() ); objMngr.registerObject( new SystemStats() ); + objMngr.registerObject( new TxPIDSettings() ); objMngr.registerObject( new TaskInfo() ); objMngr.registerObject( new VelocityActual() ); objMngr.registerObject( new VelocityDesired() ); objMngr.registerObject( new WatchdogStatus() ); + objMngr.registerObject( new Waypoint() ); + objMngr.registerObject( new WaypointActive() ); } catch (Exception e) { e.printStackTrace(); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java index 97d038cfe..2a8cd3754 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java @@ -53,15 +53,15 @@ public class VelocityActual extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm/s", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m/s", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm/s", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m/s", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm/s", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m/s", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object @@ -136,7 +136,7 @@ public class VelocityActual extends UAVDataObject { } // Constants - protected static final int OBJID = 0x43007EB0; + protected static final int OBJID = 0x5A08F61A; protected static final String NAME = "VelocityActual"; protected static String DESCRIPTION = "Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java index f39fbd6de..436ef6448 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java @@ -53,15 +53,15 @@ public class VelocityDesired extends UAVDataObject { List NorthElemNames = new ArrayList(); NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "cm/s", UAVObjectField.FieldType.INT32, NorthElemNames, null) ); + fields.add( new UAVObjectField("North", "m/s", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); List EastElemNames = new ArrayList(); EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "cm/s", UAVObjectField.FieldType.INT32, EastElemNames, null) ); + fields.add( new UAVObjectField("East", "m/s", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); List DownElemNames = new ArrayList(); DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "cm/s", UAVObjectField.FieldType.INT32, DownElemNames, null) ); + fields.add( new UAVObjectField("Down", "m/s", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); // Compute the number of bytes for this object @@ -136,7 +136,7 @@ public class VelocityDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0x25139D1A; + protected static final int OBJID = 0x9E946992; protected static final String NAME = "VelocityDesired"; protected static String DESCRIPTION = "Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates)."; protected static final boolean ISSINGLEINST = 1 == 1; From 0e6cffaaf68647f586f16ebccdf7b65004e585f9 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 16:12:45 -0500 Subject: [PATCH 249/543] Update fake telemetry object --- .../org/openpilot/androidgcs/OPTelemetryService.java | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index bc711560d..074049d79 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -222,18 +222,6 @@ public class OPTelemetryService extends Service { homeLocation.getField("Latitude").setDouble(379420315); homeLocation.getField("Longitude").setDouble(-88330078); - homeLocation.getField("ECEF").setDouble(497665694,0); - homeLocation.getField("ECEF").setDouble(-77336320,1); - homeLocation.getField("ECEF").setDouble(390037169,2); - homeLocation.getField("RNE").setDouble(-0.60757166,0); - homeLocation.getField("RNE").setDouble(0.09441550,1); - homeLocation.getField("RNE").setDouble(0.78863323,2); - homeLocation.getField("RNE").setDouble(0.15355512,3); - homeLocation.getField("RNE").setDouble(0.98814011,4); - homeLocation.getField("RNE").setDouble(0,5); - homeLocation.getField("RNE").setDouble(-0.77928013,6); - homeLocation.getField("RNE").setDouble(0.12109867,7); - homeLocation.getField("RNE").setDouble(-0.61486387,8); homeLocation.getField("Be").setDouble(26702.78710938,0); homeLocation.getField("Be").setDouble(-1468.33605957,1); homeLocation.getField("Be").setDouble(34181.78515625,2); From cd89d97bbb99e5ca498a3720b6eadb188a3332dc Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 10 May 2012 16:38:49 -0500 Subject: [PATCH 250/543] Lower all the debugging levels again --- .../org/openpilot/androidgcs/OPTelemetryService.java | 2 +- androidgcs/src/org/openpilot/uavtalk/Telemetry.java | 2 +- .../src/org/openpilot/uavtalk/TelemetryMonitor.java | 10 ++++++++-- androidgcs/src/org/openpilot/uavtalk/UAVTalk.java | 10 ++++------ 4 files changed, 14 insertions(+), 10 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 074049d79..1a4b61eb8 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -33,7 +33,7 @@ public class OPTelemetryService extends Service { // Logging settings private final String TAG = "OPTelemetryService"; - public static int LOGLEVEL = 2; + public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 11e6cb2ca..1395a5c08 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -17,7 +17,7 @@ import android.util.Log; public class Telemetry { private final String TAG = "Telemetry"; - public static int LOGLEVEL = 2; + public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 903b6b29f..87a0cdc70 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -13,7 +13,7 @@ import android.util.Log; public class TelemetryMonitor extends Observable{ private static final String TAG = "TelemetryMonitor"; - public static int LOGLEVEL = 2; + public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -204,6 +204,8 @@ public class TelemetryMonitor extends Observable{ Telemetry.TelemetryStats telStats = tel.getStats(); tel.resetStats(); + if (DEBUG) Log.d(TAG, "processStatsUpdates() - stats reset"); + // Update stats object gcsStatsObj.getField("RxDataRate").setDouble( (float)telStats.rxBytes / ((float)currentPeriod/1000.0) ); gcsStatsObj.getField("TxDataRate").setDouble( (float)telStats.txBytes / ((float)currentPeriod/1000.0) ); @@ -214,6 +216,8 @@ public class TelemetryMonitor extends Observable{ field = gcsStatsObj.getField("TxRetries"); field.setDouble(field.getDouble() + telStats.txRetries); + if (DEBUG) Log.d(TAG, "processStatsUpdates() - stats updated"); + // Check for a connection timeout boolean connectionTimeout; if ( telStats.rxObjects > 0 ) @@ -296,8 +300,10 @@ public class TelemetryMonitor extends Observable{ objects_updated = false; setChanged(); } + + if (DEBUG) Log.d(TAG, "processStatsUpdates() - before notify"); notifyObservers(); - + if (DEBUG) Log.d(TAG, "processStatsUpdates() - after notify"); } private void setPeriod(int ms) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index 5a3a9a1a5..9cdd11ccb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -12,7 +12,7 @@ import android.util.Log; public class UAVTalk extends Observable { static final String TAG = "UAVTalk"; - public static int LOGLEVEL = 2; + public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; @@ -504,8 +504,7 @@ public class UAVTalk extends Observable { case TYPE_OBJ_ACK: // All instances, not allowed for OBJ_ACK messages if (!allInstances) { - System.out.println("Received object ack: " + objId + " " + - objMngr.getObject(objId).getName()); + if (DEBUG) Log.d(TAG,"Received object ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object and update its data obj = updateObject(objId, instId, data); // Transmit ACK @@ -521,7 +520,7 @@ public class UAVTalk extends Observable { case TYPE_OBJ_REQ: // Get object, if all instances are requested get instance 0 of the // object - System.out.println("Received object request: " + objId + " " + + if (DEBUG) Log.d(TAG,"Received object request: " + objId + " " + objMngr.getObject(objId).getName()); if (allInstances) { obj = objMngr.getObject(objId); @@ -538,8 +537,7 @@ public class UAVTalk extends Observable { case TYPE_ACK: // All instances, not allowed for ACK messages if (!allInstances) { - System.out.println("Received ack: " + objId + " " + - objMngr.getObject(objId).getName()); + if (DEBUG) Log.d(TAG,"Received ack: " + objId + " " + objMngr.getObject(objId).getName()); // Get object obj = objMngr.getObject(objId, instId); // Check if an ack is pending From c736488c3bd80a9e423261adc146ed284cc5ddbd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 11:04:35 -0500 Subject: [PATCH 251/543] First step to fixing metat data representation for android --- .../org/openpilot/uavtalk/UAVMetaObject.java | 46 ++++-------- .../src/org/openpilot/uavtalk/UAVObject.java | 70 +++++++------------ .../org/openpilot/uavtalk/UAVObjectField.java | 48 ++++++++++++- 3 files changed, 85 insertions(+), 79 deletions(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index 7aab176ef..c57b6c2fe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -13,43 +13,25 @@ public class UAVMetaObject extends UAVObject { ownMetadata = new Metadata(); - ownMetadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - ownMetadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - ownMetadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - ownMetadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - ownMetadata.flightTelemetryUpdatePeriod = 0; - ownMetadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - ownMetadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; + ownMetadata.flags = 0; // TODO: Fix flags ownMetadata.gcsTelemetryUpdatePeriod = 0; - ownMetadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; ownMetadata.loggingUpdatePeriod = 0; - // Setup fields - List boolEnum = new ArrayList(); - boolEnum.add("False"); - boolEnum.add("True"); - List updateModeEnum = new ArrayList(); - updateModeEnum.add("Periodic"); - updateModeEnum.add("On Change"); - updateModeEnum.add("Manual"); - updateModeEnum.add("Never"); + List modesBitField = new ArrayList(); + modesBitField.add("FlightReadOnly"); + modesBitField.add("GCSReadOnly"); + modesBitField.add("FlightTelemetryAcked"); + modesBitField.add("GCSTelemetryAcked"); + modesBitField.add("FlightUpdatePeriodic"); + modesBitField.add("FlightUpdateOnChange"); + modesBitField.add("GCSUpdatePeriodic"); + modesBitField.add("GCSUpdateOnChange"); - List accessModeEnum = new ArrayList(); - accessModeEnum.add("Read/Write"); - accessModeEnum.add("Read Only"); - - List fields = new ArrayList(); - fields.add( new UAVObjectField("Flight Access Mode", "", UAVObjectField.FieldType.ENUM, 1, accessModeEnum) ); - fields.add( new UAVObjectField("GCS Access Mode", "", UAVObjectField.FieldType.ENUM, 1, accessModeEnum) ); - fields.add( new UAVObjectField("Flight Telemetry Acked", "", UAVObjectField.FieldType.ENUM, 1, boolEnum) ); - fields.add( new UAVObjectField("Flight Telemetry Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); - fields.add( new UAVObjectField("Flight Telemetry Update Period", "", UAVObjectField.FieldType.UINT32, 1, null) ); - fields.add( new UAVObjectField("GCS Telemetry Acked", "", UAVObjectField.FieldType.ENUM, 1, boolEnum) ); - fields.add( new UAVObjectField("GCS Telemetry Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); - fields.add( new UAVObjectField("GCS Telemetry Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); - fields.add( new UAVObjectField("Logging Update Mode", "", UAVObjectField.FieldType.ENUM, 1, updateModeEnum) ); - fields.add( new UAVObjectField("Logging Update Period", "", UAVObjectField.FieldType.UINT32, 1, null ) ); + fields.add( new UAVObjectField("Modes", "", UAVObjectField.FieldType.BITFIELD, 1, modesBitField) ); + fields.add( new UAVObjectField("Flight Telemetry Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); + fields.add( new UAVObjectField("GCS Telemetry Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); + fields.add( new UAVObjectField("Logging Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); int numBytes = 0; ListIterator li = fields.listIterator(); diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 940b076a5..20d4cb02a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -120,17 +120,10 @@ public abstract class UAVObject { * Object update mode */ public enum UpdateMode { - UPDATEMODE_PERIODIC, /** - * Automatically update object at periodic - * intervals - */ + UPDATEMODE_MANUAL, /** Manually update object, by calling the updated() function */ + UPDATEMODE_PERIODIC, /** Automatically update object at periodic intervals */ UPDATEMODE_ONCHANGE, /** Only update object when its data changes */ - UPDATEMODE_MANUAL, /** - * Manually update object, by calling the updated() - * function - */ - UPDATEMODE_NEVER - /** Object is never updated */ + UPDATEMODE_THROTTLED /** Object is updated on change, but not more often than the interval time */ }; /** @@ -140,47 +133,32 @@ public abstract class UAVObject { ACCESS_READWRITE, ACCESS_READONLY }; - /** - * Access mode - */ - public enum Acked { - FALSE, TRUE - }; - public final class Metadata { - public AccessMode flightAccess; /** - * Defines the access level for the local flight transactions (readonly - * and readwrite) + * Object metadata, each object has a meta object that holds its metadata. The metadata define + * properties for each object and can be used by multiple modules (e.g. telemetry and logger) + * + * The object metadata flags are packed into a single 16 bit integer. + * The bits in the flag field are defined as: + * + * Bit(s) Name Meaning + * ------ ---- ------- + * 0 access Defines the access level for the local transactions (readonly=0 and readwrite=1) + * 1 gcsAccess Defines the access level for the local GCS transactions (readonly=0 and readwrite=1), not used in the flight s/w + * 2 telemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) + * 3 gcsTelemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) + * 4-5 telemetryUpdateMode Update mode used by the telemetry module (UAVObjUpdateMode) + * 6-7 gcsTelemetryUpdateMode Update mode used by the GCS (UAVObjUpdateMode) */ - public AccessMode gcsAccess; - /** - * Defines the access level for the local GCS transactions (readonly and - * readwrite) - */ - public Acked flightTelemetryAcked; - /** - * Defines if an ack is required for the transactions of this object - * (1:acked, 0:not acked) - */ - public UpdateMode flightTelemetryUpdateMode; - /** Update mode used by the autopilot (UpdateMode) */ + public int flags; /** Defines flags for update and logging modes and whether an update should be ACK'd (bits defined above) */ + + /** Update period used by the telemetry module (only if telemetry mode is PERIODIC) */ public int flightTelemetryUpdatePeriod; - /** - * Update period used by the autopilot (only if telemetry mode is - * PERIODIC) - */ - public Acked gcsTelemetryAcked; - /** - * Defines if an ack is required for the transactions of this object - * (1:acked, 0:not acked) - */ - public UpdateMode gcsTelemetryUpdateMode; - /** Update mode used by the GCS (UpdateMode) */ - public int gcsTelemetryUpdatePeriod; + + /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + public int gcsTelemetryUpdatePeriod; + /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ - public UpdateMode loggingUpdateMode; - /** Update mode used by the logging module (UpdateMode) */ public int loggingUpdatePeriod; /** * Update period used by the logging module (only if logging mode is diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 286859e63..c2965f6cc 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -7,7 +7,7 @@ import java.util.List; public class UAVObjectField { - public enum FieldType { INT8, INT16, INT32, UINT8, UINT16, UINT32, FLOAT32, ENUM, STRING }; + public enum FieldType { INT8, INT16, INT32, UINT8, UINT16, UINT32, FLOAT32, ENUM, BITFIELD, STRING }; public UAVObjectField(String name, String units, FieldType type, int numElements, List options) { List elementNames = new ArrayList(); @@ -56,6 +56,8 @@ public class UAVObjectField { return "float32"; case ENUM: return "enum"; + case BITFIELD: + return "bitfield"; case STRING: return "string"; default: @@ -144,6 +146,11 @@ public class UAVObjectField { for (int index = 0; index < numElements; ++index) dataOut.put((Byte) l.get(index)); break; + case BITFIELD: + for (int index = 0; index < numElements; ++index) { + Integer val = (Integer) getValue(index); + dataOut.put(val.byteValue()); + } case STRING: // TODO: Implement strings throw new Error("Strings not yet implemented"); @@ -224,6 +231,16 @@ public class UAVObjectField { } break; } + case BITFIELD: + { + List l = (List) this.data; + for (int index = 0 ; index < numElements; ++index) { + int signedval = (int) dataIn.get(); // this sign extends it + int unsignedval = signedval & 0xff; // drop sign extension + l.set(index, (short) unsignedval); + } + break; + } case ENUM: { List l = (List) this.data; @@ -275,6 +292,9 @@ public class UAVObjectField { return options.get(val); } + case BITFIELD: + return ((List) data).get(index).intValue(); + case STRING: { //throw new Exception("Shit I should do this"); @@ -354,6 +374,12 @@ public class UAVObjectField { l.set(index, val); break; } + case BITFIELD: + { + List l = (List) this.data; + l.set(index, bound(data).shortValue()); + break; + } case STRING: { //throw new Exception("Sorry I haven't implemented strings yet"); @@ -404,6 +430,8 @@ public class UAVObjectField { return true; case ENUM: return false; + case BITFIELD: + return true; case STRING: return false; default: @@ -430,6 +458,8 @@ public class UAVObjectField { return false; case ENUM: return true; + case BITFIELD: + return false; case STRING: return true; default: @@ -493,6 +523,12 @@ public class UAVObjectField { ((ArrayList) data).add((float) 0); } break; + case BITFIELD: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((short) 0); + } + break; case ENUM: ((ArrayList) data).clear(); for(int index = 0; index < numElements; ++index) { @@ -549,6 +585,10 @@ public class UAVObjectField { data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; break; + case BITFIELD: + data = (Object) new ArrayList(this.numElements); + numBytesPerElement = 1; + break; case STRING: data = (Object) new ArrayList(this.numElements); numBytesPerElement = 1; @@ -614,6 +654,12 @@ public class UAVObjectField { if(num > 4294967295L) return 4294967295L; return num; + case BITFIELD: + if(num < 0) + return (long) 0; + if(num > 255) + return (long) 255; + return num; } return num; From 9960411ead0ae7176cef4b2c3b0e3cf3345908f1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 12:49:34 -0500 Subject: [PATCH 252/543] Finish porting the meta data changes from GCS and update all the UAVOs --- .../src/org/openpilot/uavtalk/Telemetry.java | 29 +- .../openpilot/uavtalk/TelemetryMonitor.java | 37 ++- .../src/org/openpilot/uavtalk/UAVObject.java | 194 +++++++++++- .../org/openpilot/uavtalk/UAVObjectField.java | 2 +- .../uavtalk/uavobjects/AccessoryDesired.java | 23 +- .../uavtalk/uavobjects/ActuatorCommand.java | 23 +- .../uavtalk/uavobjects/ActuatorDesired.java | 23 +- .../uavtalk/uavobjects/ActuatorSettings.java | 280 +----------------- .../uavtalk/uavobjects/AttitudeActual.java | 23 +- .../uavtalk/uavobjects/AttitudeSettings.java | 23 +- .../uavtalk/uavobjects/BaroAltitude.java | 23 +- .../uavtalk/uavobjects/CameraDesired.java | 23 +- .../uavobjects/CameraStabSettings.java | 23 +- .../uavtalk/uavobjects/FaultSettings.java | 23 +- .../uavtalk/uavobjects/FirmwareIAPObj.java | 23 +- .../uavobjects/FlightBatterySettings.java | 36 ++- .../uavobjects/FlightBatteryState.java | 30 +- .../uavtalk/uavobjects/FlightPlanControl.java | 23 +- .../uavobjects/FlightPlanSettings.java | 23 +- .../uavtalk/uavobjects/FlightPlanStatus.java | 23 +- .../uavtalk/uavobjects/FlightStatus.java | 26 +- .../uavobjects/FlightTelemetryStats.java | 23 +- .../uavtalk/uavobjects/GCSReceiver.java | 27 +- .../uavtalk/uavobjects/GCSTelemetryStats.java | 23 +- .../uavtalk/uavobjects/GPSPosition.java | 23 +- .../uavtalk/uavobjects/GPSSatellites.java | 23 +- .../openpilot/uavtalk/uavobjects/GPSTime.java | 23 +- .../uavtalk/uavobjects/GuidanceSettings.java | 211 ------------- .../uavtalk/uavobjects/HomeLocation.java | 23 +- .../uavtalk/uavobjects/HwSettings.java | 44 +-- .../uavtalk/uavobjects/I2CStats.java | 23 +- .../uavobjects/ManualControlCommand.java | 23 +- .../uavobjects/ManualControlSettings.java | 48 ++- .../uavtalk/uavobjects/MixerSettings.java | 23 +- .../uavtalk/uavobjects/MixerStatus.java | 23 +- .../uavtalk/uavobjects/NedAccel.java | 23 +- .../uavtalk/uavobjects/ObjectPersistence.java | 26 +- .../uavtalk/uavobjects/PositionActual.java | 23 +- .../uavtalk/uavobjects/PositionDesired.java | 147 --------- .../uavtalk/uavobjects/RateDesired.java | 23 +- .../uavtalk/uavobjects/ReceiverActivity.java | 23 +- .../uavtalk/uavobjects/SonarAltitude.java | 23 +- .../uavobjects/StabilizationDesired.java | 26 +- .../uavobjects/StabilizationSettings.java | 78 ++++- .../uavtalk/uavobjects/SystemAlarms.java | 29 +- .../uavtalk/uavobjects/SystemSettings.java | 34 ++- .../uavtalk/uavobjects/SystemStats.java | 23 +- .../uavtalk/uavobjects/TaskInfo.java | 40 +-- .../uavobjects/UAVObjectsInitialize.java | 21 +- .../uavtalk/uavobjects/VelocityActual.java | 23 +- .../uavtalk/uavobjects/VelocityDesired.java | 23 +- .../uavtalk/uavobjects/WatchdogStatus.java | 23 +- .../templates/uavobjecttemplate.java | 23 +- 53 files changed, 880 insertions(+), 1244 deletions(-) delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java delete mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 1395a5c08..2ee5ab9a4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -10,8 +10,6 @@ import java.util.Queue; import java.util.Timer; import java.util.TimerTask; -import org.openpilot.uavtalk.UAVObject.Acked; - import android.util.Log; public class Telemetry { @@ -20,7 +18,7 @@ public class Telemetry { public static int LOGLEVEL = 0; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; - + public class TelemetryStats { public int txBytes; public int rxBytes; @@ -50,7 +48,7 @@ public class Telemetry { boolean allInstances; boolean objRequest; int retriesRemaining; - Acked acked; + boolean acked; } ; /** @@ -249,7 +247,7 @@ public class Telemetry { // Setup object depending on update mode int eventMask; - if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_PERIODIC ) + if ( metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_PERIODIC ) { // Set update period setUpdatePeriod(obj, metadata.gcsTelemetryUpdatePeriod); @@ -260,7 +258,7 @@ public class Telemetry { connectToObjectInstances(obj, eventMask); } - else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) + else if ( metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) { // Set update period setUpdatePeriod(obj, 0); @@ -271,7 +269,11 @@ public class Telemetry { connectToObjectInstances(obj, eventMask); } - else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_MANUAL ) + else if ( metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_THROTTLED ) + { + // TODO + } + else if ( metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_MANUAL ) { // Set update period setUpdatePeriod(obj, 0); @@ -282,13 +284,6 @@ public class Telemetry { connectToObjectInstances(obj, eventMask); } - else if ( metadata.gcsTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_NEVER ) - { - // Set update period - setUpdatePeriod(obj, 0); - // Disconnect from object - connectToObjectInstances(obj, 0); - } } /** @@ -360,10 +355,10 @@ public class Telemetry { } else { - utalk.sendObject(transInfo.obj, transInfo.acked == Acked.TRUE, transInfo.allInstances); + utalk.sendObject(transInfo.obj, transInfo.acked, transInfo.allInstances); } // Start timer if a response is expected - if ( transInfo.objRequest || transInfo.acked == Acked.TRUE ) + if ( transInfo.objRequest || transInfo.acked ) { transTimerSetPeriod(REQ_TIMEOUT_MS); } @@ -476,7 +471,7 @@ public class Telemetry { transInfo.obj = objInfo.obj; transInfo.allInstances = objInfo.allInstances; transInfo.retriesRemaining = MAX_RETRIES; - transInfo.acked = metadata.gcsTelemetryAcked; + transInfo.acked = metadata.GetGcsTelemetryAcked(); if ( objInfo.event == EV_UPDATED || objInfo.event == EV_UPDATED_MANUAL ) { transInfo.objRequest = false; diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 87a0cdc70..d1d7a9c44 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -76,27 +76,24 @@ public class TelemetryMonitor extends Observable{ List instList = objListIterator.next(); UAVObject obj = instList.get(0); UAVObject.Metadata mdata = obj.getMetadata(); - if ( mdata.gcsTelemetryUpdateMode != UAVObject.UpdateMode.UPDATEMODE_NEVER ) + if ( obj.isMetadata() ) { - if ( obj.isMetadata() ) - { - queue.add(obj); - } - else /* Data object */ - { - UAVDataObject dobj = (UAVDataObject) obj; - if ( dobj.isSettings() ) - { - queue.add(obj); - } - else - { - if ( mdata.flightTelemetryUpdateMode == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) - { - queue.add(obj); - } - } - } + queue.add(obj); + } + else /* Data object */ + { + UAVDataObject dobj = (UAVDataObject) obj; + if ( dobj.isSettings() ) + { + queue.add(obj); + } + else + { + if ( mdata.GetFlightTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE ) + { + queue.add(obj); + } + } } } // Start retrieving diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 20d4cb02a..28c279040 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -133,7 +133,15 @@ public abstract class UAVObject { ACCESS_READWRITE, ACCESS_READONLY }; - public final class Metadata { + public final static int UAVOBJ_ACCESS_SHIFT = 0; + public final static int UAVOBJ_GCS_ACCESS_SHIFT = 1; + public final static int UAVOBJ_TELEMETRY_ACKED_SHIFT = 2; + public final static int UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT = 3; + public final static int UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT = 4; + public final static int UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT = 6; + public final static int UAVOBJ_UPDATE_MODE_MASK = 0x3; + + public final static class Metadata { /** * Object metadata, each object has a meta object that holds its metadata. The metadata define * properties for each object and can be used by multiple modules (e.g. telemetry and logger) @@ -164,6 +172,190 @@ public abstract class UAVObject { * Update period used by the logging module (only if logging mode is * PERIODIC) */ + + /** + * @brief Helper method for metadata accessors + * @param var The starting value + * @param shift The offset of these bits + * @param value The new value + * @param mask The mask of these bits + * @return + */ + private void SET_BITS(int shift, int value, int mask) { + this.flags = (this.flags & ~(mask << shift)) | (value << shift); + } + + /** + * Get the UAVObject metadata access member + * \return the access type + */ + public AccessMode GetFlightAccess() + { + return AccessModeEnum((this.flags >> UAVOBJ_ACCESS_SHIFT) & 1); + } + + /** + * Set the UAVObject metadata access member + * \param[in] mode The access mode + */ + public void SetFlightAccess(Metadata metadata, AccessMode mode) + { + // Need to convert java enums which have no numeric value to bits + SET_BITS(UAVOBJ_ACCESS_SHIFT, AccessModeNum(mode), 1); + } + + /** + * Get the UAVObject metadata GCS access member + * \return the GCS access type + */ + public AccessMode GetGcsAccess() + { + return AccessModeEnum((this.flags >> UAVOBJ_GCS_ACCESS_SHIFT) & 1); + } + + /** + * Set the UAVObject metadata GCS access member + * \param[in] mode The access mode + */ + public void SetGcsAccess(Metadata metadata, AccessMode mode) { + // Need to convert java enums which have no numeric value to bits + SET_BITS(UAVOBJ_GCS_ACCESS_SHIFT, AccessModeNum(mode), 1); + } + + /** + * Get the UAVObject metadata telemetry acked member + * \return the telemetry acked boolean + */ + public boolean GetFlightTelemetryAcked() { + return (((this.flags >> UAVOBJ_TELEMETRY_ACKED_SHIFT) & 1) == 1); + } + + /** + * Set the UAVObject metadata telemetry acked member + * \param[in] val The telemetry acked boolean + */ + public void SetFlightTelemetryAcked(boolean val) { + SET_BITS(UAVOBJ_TELEMETRY_ACKED_SHIFT, val ? 1 : 0, 1); + } + + /** + * Get the UAVObject metadata GCS telemetry acked member + * \return the telemetry acked boolean + */ + public boolean GetGcsTelemetryAcked() { + return ((this.flags >> UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT) & 1) == 1; + } + + /** + * Set the UAVObject metadata GCS telemetry acked member + * \param[in] val The GCS telemetry acked boolean + */ + public void SetGcsTelemetryAcked(boolean val) { + SET_BITS(UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT, val ? 1 : 0, 1); + } + + /** + * Maps from the bitfield number to the symbolic java enumeration + * @param num The value in the bitfield after shifting + * @return The update mode + */ + public static AccessMode AccessModeEnum(int num) { + switch(num) { + case 0: + return AccessMode.ACCESS_READONLY; + case 1: + return AccessMode.ACCESS_READWRITE; + } + return AccessMode.ACCESS_READONLY; + } + + /** + * Maps from the java symbolic enumeration of update mode to the bitfield value + * @param e The update mode + * @return The numeric value to use on the wire + */ + public static int AccessModeNum(AccessMode e) { + switch(e) { + case ACCESS_READONLY: + return 0; + case ACCESS_READWRITE: + return 1; + } + return 0; + } + + /** + * Maps from the bitfield number to the symbolic java enumeration + * @param num The value in the bitfield after shifting + * @return The update mode + */ + public static UpdateMode UpdateModeEnum(int num) { + switch(num) { + case 0: + return UpdateMode.UPDATEMODE_MANUAL; + case 1: + return UpdateMode.UPDATEMODE_PERIODIC; + case 2: + return UpdateMode.UPDATEMODE_ONCHANGE; + default: + return UpdateMode.UPDATEMODE_THROTTLED; + } + } + + /** + * Maps from the java symbolic enumeration of update mode to the bitfield value + * @param e The update mode + * @return The numeric value to use on the wire + */ + public static int UpdateModeNum(UpdateMode e) { + switch(e) { + case UPDATEMODE_MANUAL: + return 0; + case UPDATEMODE_PERIODIC: + return 1; + case UPDATEMODE_ONCHANGE: + return 2; + case UPDATEMODE_THROTTLED: + return 3; + } + return 0; + } + + /** + * Get the UAVObject metadata telemetry update mode + * \return the telemetry update mode + */ + public UpdateMode GetFlightTelemetryUpdateMode() { + return UpdateModeEnum((this.flags >> UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK); + } + + /** + * Set the UAVObject metadata telemetry update mode member + * \param[in] metadata The metadata object + * \param[in] val The telemetry update mode + */ + public void SetFlightTelemetryUpdateMode(UpdateMode val) { + SET_BITS(UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT, UpdateModeNum(val), UAVOBJ_UPDATE_MODE_MASK); + } + + /** + * Get the UAVObject metadata GCS telemetry update mode + * \param[in] metadata The metadata object + * \return the GCS telemetry update mode + */ + public UpdateMode GetGcsTelemetryUpdateMode() { + return UpdateModeEnum((this.flags >> UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT) & UAVOBJ_UPDATE_MODE_MASK); + } + + /** + * Set the UAVObject metadata GCS telemetry update mode member + * \param[in] metadata The metadata object + * \param[in] val The GCS telemetry update mode + */ + public void SetGcsTelemetryUpdateMode(UpdateMode val) { + SET_BITS(UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT, UpdateModeNum(val), UAVOBJ_UPDATE_MODE_MASK); + } + }; public UAVObject(int objID, Boolean isSingleInst, String name) { diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index c2965f6cc..3ed221079 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -314,7 +314,7 @@ public class UAVObjectField { // Get metadata UAVObject.Metadata mdata = obj.getMetadata(); // Update value if the access mode permits - if ( mdata.gcsAccess == UAVObject.AccessMode.ACCESS_READWRITE ) + if ( mdata.GetGcsAccess() == UAVObject.AccessMode.ACCESS_READWRITE ) { switch (type) { diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java index 13c63dfdd..4b7c875a7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java @@ -78,18 +78,17 @@ public class AccessoryDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java index 08f2ebefe..0120e0ce7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java @@ -99,18 +99,17 @@ public class ActuatorCommand extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java index 03ff1985c..a00517906 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java @@ -98,18 +98,17 @@ public class ActuatorDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java index 71b0bb49f..2257da346 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java @@ -97,246 +97,6 @@ public class ActuatorSettings extends UAVDataObject { ChannelMinElemNames.add("9"); fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); - List FixedWingRoll1ElemNames = new ArrayList(); - FixedWingRoll1ElemNames.add("0"); - List FixedWingRoll1EnumOptions = new ArrayList(); - FixedWingRoll1EnumOptions.add("Channel1"); - FixedWingRoll1EnumOptions.add("Channel2"); - FixedWingRoll1EnumOptions.add("Channel3"); - FixedWingRoll1EnumOptions.add("Channel4"); - FixedWingRoll1EnumOptions.add("Channel5"); - FixedWingRoll1EnumOptions.add("Channel6"); - FixedWingRoll1EnumOptions.add("Channel7"); - FixedWingRoll1EnumOptions.add("Channel8"); - FixedWingRoll1EnumOptions.add("Channel9"); - FixedWingRoll1EnumOptions.add("Channel10"); - FixedWingRoll1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingRoll1", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll1ElemNames, FixedWingRoll1EnumOptions) ); - - List FixedWingRoll2ElemNames = new ArrayList(); - FixedWingRoll2ElemNames.add("0"); - List FixedWingRoll2EnumOptions = new ArrayList(); - FixedWingRoll2EnumOptions.add("Channel1"); - FixedWingRoll2EnumOptions.add("Channel2"); - FixedWingRoll2EnumOptions.add("Channel3"); - FixedWingRoll2EnumOptions.add("Channel4"); - FixedWingRoll2EnumOptions.add("Channel5"); - FixedWingRoll2EnumOptions.add("Channel6"); - FixedWingRoll2EnumOptions.add("Channel7"); - FixedWingRoll2EnumOptions.add("Channel8"); - FixedWingRoll2EnumOptions.add("Channel9"); - FixedWingRoll2EnumOptions.add("Channel10"); - FixedWingRoll2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingRoll2", "channel", UAVObjectField.FieldType.ENUM, FixedWingRoll2ElemNames, FixedWingRoll2EnumOptions) ); - - List FixedWingPitch1ElemNames = new ArrayList(); - FixedWingPitch1ElemNames.add("0"); - List FixedWingPitch1EnumOptions = new ArrayList(); - FixedWingPitch1EnumOptions.add("Channel1"); - FixedWingPitch1EnumOptions.add("Channel2"); - FixedWingPitch1EnumOptions.add("Channel3"); - FixedWingPitch1EnumOptions.add("Channel4"); - FixedWingPitch1EnumOptions.add("Channel5"); - FixedWingPitch1EnumOptions.add("Channel6"); - FixedWingPitch1EnumOptions.add("Channel7"); - FixedWingPitch1EnumOptions.add("Channel8"); - FixedWingPitch1EnumOptions.add("Channel9"); - FixedWingPitch1EnumOptions.add("Channel10"); - FixedWingPitch1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingPitch1", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch1ElemNames, FixedWingPitch1EnumOptions) ); - - List FixedWingPitch2ElemNames = new ArrayList(); - FixedWingPitch2ElemNames.add("0"); - List FixedWingPitch2EnumOptions = new ArrayList(); - FixedWingPitch2EnumOptions.add("Channel1"); - FixedWingPitch2EnumOptions.add("Channel2"); - FixedWingPitch2EnumOptions.add("Channel3"); - FixedWingPitch2EnumOptions.add("Channel4"); - FixedWingPitch2EnumOptions.add("Channel5"); - FixedWingPitch2EnumOptions.add("Channel6"); - FixedWingPitch2EnumOptions.add("Channel7"); - FixedWingPitch2EnumOptions.add("Channel8"); - FixedWingPitch2EnumOptions.add("Channel9"); - FixedWingPitch2EnumOptions.add("Channel10"); - FixedWingPitch2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingPitch2", "channel", UAVObjectField.FieldType.ENUM, FixedWingPitch2ElemNames, FixedWingPitch2EnumOptions) ); - - List FixedWingYaw1ElemNames = new ArrayList(); - FixedWingYaw1ElemNames.add("0"); - List FixedWingYaw1EnumOptions = new ArrayList(); - FixedWingYaw1EnumOptions.add("Channel1"); - FixedWingYaw1EnumOptions.add("Channel2"); - FixedWingYaw1EnumOptions.add("Channel3"); - FixedWingYaw1EnumOptions.add("Channel4"); - FixedWingYaw1EnumOptions.add("Channel5"); - FixedWingYaw1EnumOptions.add("Channel6"); - FixedWingYaw1EnumOptions.add("Channel7"); - FixedWingYaw1EnumOptions.add("Channel8"); - FixedWingYaw1EnumOptions.add("Channel9"); - FixedWingYaw1EnumOptions.add("Channel10"); - FixedWingYaw1EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingYaw1", "channel", UAVObjectField.FieldType.ENUM, FixedWingYaw1ElemNames, FixedWingYaw1EnumOptions) ); - - List FixedWingYaw2ElemNames = new ArrayList(); - FixedWingYaw2ElemNames.add("0"); - List FixedWingYaw2EnumOptions = new ArrayList(); - FixedWingYaw2EnumOptions.add("Channel1"); - FixedWingYaw2EnumOptions.add("Channel2"); - FixedWingYaw2EnumOptions.add("Channel3"); - FixedWingYaw2EnumOptions.add("Channel4"); - FixedWingYaw2EnumOptions.add("Channel5"); - FixedWingYaw2EnumOptions.add("Channel6"); - FixedWingYaw2EnumOptions.add("Channel7"); - FixedWingYaw2EnumOptions.add("Channel8"); - FixedWingYaw2EnumOptions.add("Channel9"); - FixedWingYaw2EnumOptions.add("Channel10"); - FixedWingYaw2EnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingYaw2", "channel", UAVObjectField.FieldType.ENUM, FixedWingYaw2ElemNames, FixedWingYaw2EnumOptions) ); - - List FixedWingThrottleElemNames = new ArrayList(); - FixedWingThrottleElemNames.add("0"); - List FixedWingThrottleEnumOptions = new ArrayList(); - FixedWingThrottleEnumOptions.add("Channel1"); - FixedWingThrottleEnumOptions.add("Channel2"); - FixedWingThrottleEnumOptions.add("Channel3"); - FixedWingThrottleEnumOptions.add("Channel4"); - FixedWingThrottleEnumOptions.add("Channel5"); - FixedWingThrottleEnumOptions.add("Channel6"); - FixedWingThrottleEnumOptions.add("Channel7"); - FixedWingThrottleEnumOptions.add("Channel8"); - FixedWingThrottleEnumOptions.add("Channel9"); - FixedWingThrottleEnumOptions.add("Channel10"); - FixedWingThrottleEnumOptions.add("None"); - fields.add( new UAVObjectField("FixedWingThrottle", "channel", UAVObjectField.FieldType.ENUM, FixedWingThrottleElemNames, FixedWingThrottleEnumOptions) ); - - List VTOLMotorNElemNames = new ArrayList(); - VTOLMotorNElemNames.add("0"); - List VTOLMotorNEnumOptions = new ArrayList(); - VTOLMotorNEnumOptions.add("Channel1"); - VTOLMotorNEnumOptions.add("Channel2"); - VTOLMotorNEnumOptions.add("Channel3"); - VTOLMotorNEnumOptions.add("Channel4"); - VTOLMotorNEnumOptions.add("Channel5"); - VTOLMotorNEnumOptions.add("Channel6"); - VTOLMotorNEnumOptions.add("Channel7"); - VTOLMotorNEnumOptions.add("Channel8"); - VTOLMotorNEnumOptions.add("Channel9"); - VTOLMotorNEnumOptions.add("Channel10"); - VTOLMotorNEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorN", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNElemNames, VTOLMotorNEnumOptions) ); - - List VTOLMotorNEElemNames = new ArrayList(); - VTOLMotorNEElemNames.add("0"); - List VTOLMotorNEEnumOptions = new ArrayList(); - VTOLMotorNEEnumOptions.add("Channel1"); - VTOLMotorNEEnumOptions.add("Channel2"); - VTOLMotorNEEnumOptions.add("Channel3"); - VTOLMotorNEEnumOptions.add("Channel4"); - VTOLMotorNEEnumOptions.add("Channel5"); - VTOLMotorNEEnumOptions.add("Channel6"); - VTOLMotorNEEnumOptions.add("Channel7"); - VTOLMotorNEEnumOptions.add("Channel8"); - VTOLMotorNEEnumOptions.add("Channel9"); - VTOLMotorNEEnumOptions.add("Channel10"); - VTOLMotorNEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorNE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNEElemNames, VTOLMotorNEEnumOptions) ); - - List VTOLMotorEElemNames = new ArrayList(); - VTOLMotorEElemNames.add("0"); - List VTOLMotorEEnumOptions = new ArrayList(); - VTOLMotorEEnumOptions.add("Channel1"); - VTOLMotorEEnumOptions.add("Channel2"); - VTOLMotorEEnumOptions.add("Channel3"); - VTOLMotorEEnumOptions.add("Channel4"); - VTOLMotorEEnumOptions.add("Channel5"); - VTOLMotorEEnumOptions.add("Channel6"); - VTOLMotorEEnumOptions.add("Channel7"); - VTOLMotorEEnumOptions.add("Channel8"); - VTOLMotorEEnumOptions.add("Channel9"); - VTOLMotorEEnumOptions.add("Channel10"); - VTOLMotorEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorEElemNames, VTOLMotorEEnumOptions) ); - - List VTOLMotorSEElemNames = new ArrayList(); - VTOLMotorSEElemNames.add("0"); - List VTOLMotorSEEnumOptions = new ArrayList(); - VTOLMotorSEEnumOptions.add("Channel1"); - VTOLMotorSEEnumOptions.add("Channel2"); - VTOLMotorSEEnumOptions.add("Channel3"); - VTOLMotorSEEnumOptions.add("Channel4"); - VTOLMotorSEEnumOptions.add("Channel5"); - VTOLMotorSEEnumOptions.add("Channel6"); - VTOLMotorSEEnumOptions.add("Channel7"); - VTOLMotorSEEnumOptions.add("Channel8"); - VTOLMotorSEEnumOptions.add("Channel9"); - VTOLMotorSEEnumOptions.add("Channel10"); - VTOLMotorSEEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorSE", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSEElemNames, VTOLMotorSEEnumOptions) ); - - List VTOLMotorSElemNames = new ArrayList(); - VTOLMotorSElemNames.add("0"); - List VTOLMotorSEnumOptions = new ArrayList(); - VTOLMotorSEnumOptions.add("Channel1"); - VTOLMotorSEnumOptions.add("Channel2"); - VTOLMotorSEnumOptions.add("Channel3"); - VTOLMotorSEnumOptions.add("Channel4"); - VTOLMotorSEnumOptions.add("Channel5"); - VTOLMotorSEnumOptions.add("Channel6"); - VTOLMotorSEnumOptions.add("Channel7"); - VTOLMotorSEnumOptions.add("Channel8"); - VTOLMotorSEnumOptions.add("Channel9"); - VTOLMotorSEnumOptions.add("Channel10"); - VTOLMotorSEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorS", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSElemNames, VTOLMotorSEnumOptions) ); - - List VTOLMotorSWElemNames = new ArrayList(); - VTOLMotorSWElemNames.add("0"); - List VTOLMotorSWEnumOptions = new ArrayList(); - VTOLMotorSWEnumOptions.add("Channel1"); - VTOLMotorSWEnumOptions.add("Channel2"); - VTOLMotorSWEnumOptions.add("Channel3"); - VTOLMotorSWEnumOptions.add("Channel4"); - VTOLMotorSWEnumOptions.add("Channel5"); - VTOLMotorSWEnumOptions.add("Channel6"); - VTOLMotorSWEnumOptions.add("Channel7"); - VTOLMotorSWEnumOptions.add("Channel8"); - VTOLMotorSWEnumOptions.add("Channel9"); - VTOLMotorSWEnumOptions.add("Channel10"); - VTOLMotorSWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorSW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorSWElemNames, VTOLMotorSWEnumOptions) ); - - List VTOLMotorWElemNames = new ArrayList(); - VTOLMotorWElemNames.add("0"); - List VTOLMotorWEnumOptions = new ArrayList(); - VTOLMotorWEnumOptions.add("Channel1"); - VTOLMotorWEnumOptions.add("Channel2"); - VTOLMotorWEnumOptions.add("Channel3"); - VTOLMotorWEnumOptions.add("Channel4"); - VTOLMotorWEnumOptions.add("Channel5"); - VTOLMotorWEnumOptions.add("Channel6"); - VTOLMotorWEnumOptions.add("Channel7"); - VTOLMotorWEnumOptions.add("Channel8"); - VTOLMotorWEnumOptions.add("Channel9"); - VTOLMotorWEnumOptions.add("Channel10"); - VTOLMotorWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorWElemNames, VTOLMotorWEnumOptions) ); - - List VTOLMotorNWElemNames = new ArrayList(); - VTOLMotorNWElemNames.add("0"); - List VTOLMotorNWEnumOptions = new ArrayList(); - VTOLMotorNWEnumOptions.add("Channel1"); - VTOLMotorNWEnumOptions.add("Channel2"); - VTOLMotorNWEnumOptions.add("Channel3"); - VTOLMotorNWEnumOptions.add("Channel4"); - VTOLMotorNWEnumOptions.add("Channel5"); - VTOLMotorNWEnumOptions.add("Channel6"); - VTOLMotorNWEnumOptions.add("Channel7"); - VTOLMotorNWEnumOptions.add("Channel8"); - VTOLMotorNWEnumOptions.add("Channel9"); - VTOLMotorNWEnumOptions.add("Channel10"); - VTOLMotorNWEnumOptions.add("None"); - fields.add( new UAVObjectField("VTOLMotorNW", "channel", UAVObjectField.FieldType.ENUM, VTOLMotorNWElemNames, VTOLMotorNWEnumOptions) ); - List ChannelTypeElemNames = new ArrayList(); ChannelTypeElemNames.add("0"); ChannelTypeElemNames.add("1"); @@ -398,18 +158,17 @@ public class ActuatorSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -454,21 +213,6 @@ public class ActuatorSettings extends UAVDataObject { getField("ChannelMin").setValue(1000,7); getField("ChannelMin").setValue(1000,8); getField("ChannelMin").setValue(1000,9); - getField("FixedWingRoll1").setValue("None"); - getField("FixedWingRoll2").setValue("None"); - getField("FixedWingPitch1").setValue("None"); - getField("FixedWingPitch2").setValue("None"); - getField("FixedWingYaw1").setValue("None"); - getField("FixedWingYaw2").setValue("None"); - getField("FixedWingThrottle").setValue("None"); - getField("VTOLMotorN").setValue("None"); - getField("VTOLMotorNE").setValue("None"); - getField("VTOLMotorE").setValue("None"); - getField("VTOLMotorSE").setValue("None"); - getField("VTOLMotorS").setValue("None"); - getField("VTOLMotorSW").setValue("None"); - getField("VTOLMotorW").setValue("None"); - getField("VTOLMotorNW").setValue("None"); getField("ChannelType").setValue("PWM",0); getField("ChannelType").setValue("PWM",1); getField("ChannelType").setValue("PWM",2); @@ -518,7 +262,7 @@ public class ActuatorSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF2875746; + protected static final int OBJID = 0x7D555646; protected static final String NAME = "ActuatorSettings"; protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java index 7c9272cad..b117e501a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java @@ -102,18 +102,17 @@ public class AttitudeActual extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 100; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 100; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java index 3034a99ad..9bcce7bf3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java @@ -130,18 +130,17 @@ public class AttitudeSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java index ecde53985..cd649f84c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java @@ -86,18 +86,17 @@ public class BaroAltitude extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java index 7a36ec1ea..34c23e612 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java @@ -86,18 +86,17 @@ public class CameraDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java index a8e03df32..0b2f3b3f5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java @@ -125,18 +125,17 @@ public class CameraStabSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java index b22b8185e..8da58f793 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java @@ -85,18 +85,17 @@ public class FaultSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java index 71c681bd2..58fadcee5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java @@ -152,18 +152,17 @@ public class FirmwareIAPObj extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java index a3bc23eb3..850f64103 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java @@ -80,9 +80,12 @@ public class FlightBatterySettings extends UAVDataObject { fields.add( new UAVObjectField("NbCells", "", UAVObjectField.FieldType.UINT8, NbCellsElemNames, null) ); List SensorTypeElemNames = new ArrayList(); - SensorTypeElemNames.add("0"); + SensorTypeElemNames.add("BatteryCurrent"); + SensorTypeElemNames.add("BatteryVoltage"); + SensorTypeElemNames.add("BoardVoltage"); List SensorTypeEnumOptions = new ArrayList(); - SensorTypeEnumOptions.add("None"); + SensorTypeEnumOptions.add("Disabled"); + SensorTypeEnumOptions.add("Enabled"); fields.add( new UAVObjectField("SensorType", "", UAVObjectField.FieldType.ENUM, SensorTypeElemNames, SensorTypeEnumOptions) ); @@ -108,18 +111,17 @@ public class FlightBatterySettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -137,7 +139,9 @@ public class FlightBatterySettings extends UAVDataObject { getField("SensorCalibrations").setValue(1,1); getField("Type").setValue("LiPo"); getField("NbCells").setValue(3); - getField("SensorType").setValue("None"); + getField("SensorType").setValue("Disabled",0); + getField("SensorType").setValue("Disabled",1); + getField("SensorType").setValue("Disabled",2); } @@ -166,7 +170,7 @@ public class FlightBatterySettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF172BB18; + protected static final int OBJID = 0x94AC6AD2; protected static final String NAME = "FlightBatterySettings"; protected static String DESCRIPTION = "Flight Battery configuration."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java index 82fcfae47..d54648ad5 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java @@ -59,6 +59,10 @@ public class FlightBatteryState extends UAVDataObject { CurrentElemNames.add("0"); fields.add( new UAVObjectField("Current", "A", UAVObjectField.FieldType.FLOAT32, CurrentElemNames, null) ); + List BoardSupplyVoltageElemNames = new ArrayList(); + BoardSupplyVoltageElemNames.add("0"); + fields.add( new UAVObjectField("BoardSupplyVoltage", "V", UAVObjectField.FieldType.FLOAT32, BoardSupplyVoltageElemNames, null) ); + List PeakCurrentElemNames = new ArrayList(); PeakCurrentElemNames.add("0"); fields.add( new UAVObjectField("PeakCurrent", "A", UAVObjectField.FieldType.FLOAT32, PeakCurrentElemNames, null) ); @@ -98,18 +102,17 @@ public class FlightBatteryState extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READONLY; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -122,6 +125,7 @@ public class FlightBatteryState extends UAVDataObject { { getField("Voltage").setValue(0); getField("Current").setValue(0); + getField("BoardSupplyVoltage").setValue(0); getField("PeakCurrent").setValue(0); getField("AvgCurrent").setValue(0); getField("ConsumedEnergy").setValue(0); @@ -154,7 +158,7 @@ public class FlightBatteryState extends UAVDataObject { } // Constants - protected static final int OBJID = 0x8C0D756; + protected static final int OBJID = 0xD2083596; protected static final String NAME = "FlightBatteryState"; protected static String DESCRIPTION = "Battery status information."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java index dbe959f96..cdea28a0f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java @@ -82,18 +82,17 @@ public class FlightPlanControl extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java index 6fc39a26e..184bbd1b7 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java @@ -78,18 +78,17 @@ public class FlightPlanSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java index 7b78bce71..8aa152789 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java @@ -119,18 +119,17 @@ public class FlightPlanStatus extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 2000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 2000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java index ac3812aa6..38697e573 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java @@ -70,6 +70,7 @@ public class FlightStatus extends UAVDataObject { FlightModeEnumOptions.add("VelocityControl"); FlightModeEnumOptions.add("PositionHold"); FlightModeEnumOptions.add("PathPlanner"); + FlightModeEnumOptions.add("RTH"); fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); @@ -95,18 +96,17 @@ public class FlightStatus extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 5000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 5000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -146,7 +146,7 @@ public class FlightStatus extends UAVDataObject { } // Constants - protected static final int OBJID = 0x19B92D8; + protected static final int OBJID = 0x884FEF66; protected static final String NAME = "FlightStatus"; protected static String DESCRIPTION = "Contains major flight status information for other modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java index 403ea1d5e..3a042f52e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightTelemetryStats.java @@ -103,18 +103,17 @@ public class FlightTelemetryStats extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 5000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 5000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 5000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 5000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java index 3cb3811ae..05fa87efb 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java @@ -58,6 +58,8 @@ public class GCSReceiver extends UAVDataObject { ChannelElemNames.add("3"); ChannelElemNames.add("4"); ChannelElemNames.add("5"); + ChannelElemNames.add("6"); + ChannelElemNames.add("7"); fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); @@ -83,18 +85,17 @@ public class GCSReceiver extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READONLY; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -133,7 +134,7 @@ public class GCSReceiver extends UAVDataObject { } // Constants - protected static final int OBJID = 0xCC7E2BBC; + protected static final int OBJID = 0xCC7E1470; protected static final String NAME = "GCSReceiver"; protected static String DESCRIPTION = "A receiver channel group carried over the telemetry link."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java index b32f551ce..754272c8c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSTelemetryStats.java @@ -103,18 +103,17 @@ public class GCSTelemetryStats extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.gcsTelemetryUpdatePeriod = 5000; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 5000; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java index 5f4e20b46..c2c8544a9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java @@ -123,18 +123,17 @@ public class GPSPosition extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java index bb331132d..0f5b0161a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java @@ -154,18 +154,17 @@ public class GPSSatellites extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 30000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 30000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java index 5aa4df7bf..7095aa18e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java @@ -98,18 +98,17 @@ public class GPSTime extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 30000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 30000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java deleted file mode 100644 index 5510a901d..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ /dev/null @@ -1,211 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref GuidanceModule - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref GuidanceModule - -generated from guidancesettings.xml - **/ -public class GuidanceSettings extends UAVDataObject { - - public GuidanceSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List HorizontalPosPIElemNames = new ArrayList(); - HorizontalPosPIElemNames.add("Kp"); - HorizontalPosPIElemNames.add("Ki"); - HorizontalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalPosPI", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); - - List HorizontalVelPIDElemNames = new ArrayList(); - HorizontalVelPIDElemNames.add("Kp"); - HorizontalVelPIDElemNames.add("Ki"); - HorizontalVelPIDElemNames.add("Kd"); - HorizontalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalVelPID", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); - - List VerticalPosPIElemNames = new ArrayList(); - VerticalPosPIElemNames.add("Kp"); - VerticalPosPIElemNames.add("Ki"); - VerticalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("VerticalPosPI", "", UAVObjectField.FieldType.FLOAT32, VerticalPosPIElemNames, null) ); - - List VerticalVelPIDElemNames = new ArrayList(); - VerticalVelPIDElemNames.add("Kp"); - VerticalVelPIDElemNames.add("Ki"); - VerticalVelPIDElemNames.add("Kd"); - VerticalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); - - List MaxRollPitchElemNames = new ArrayList(); - MaxRollPitchElemNames.add("0"); - fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); - - List UpdatePeriodElemNames = new ArrayList(); - UpdatePeriodElemNames.add("0"); - fields.add( new UAVObjectField("UpdatePeriod", "", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); - - List HorizontalVelMaxElemNames = new ArrayList(); - HorizontalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("HorizontalVelMax", "m/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); - - List VerticalVelMaxElemNames = new ArrayList(); - VerticalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); - - List GuidanceModeElemNames = new ArrayList(); - GuidanceModeElemNames.add("0"); - List GuidanceModeEnumOptions = new ArrayList(); - GuidanceModeEnumOptions.add("DUAL_LOOP"); - GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); - fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); - - List ThrottleControlElemNames = new ArrayList(); - ThrottleControlElemNames.add("0"); - List ThrottleControlEnumOptions = new ArrayList(); - ThrottleControlEnumOptions.add("FALSE"); - ThrottleControlEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("HorizontalPosPI").setValue(0.1,0); - getField("HorizontalPosPI").setValue(0.001,1); - getField("HorizontalPosPI").setValue(300,2); - getField("HorizontalVelPID").setValue(0.05,0); - getField("HorizontalVelPID").setValue(0.002,1); - getField("HorizontalVelPID").setValue(0,2); - getField("HorizontalVelPID").setValue(1000,3); - getField("VerticalPosPI").setValue(0.1,0); - getField("VerticalPosPI").setValue(0.001,1); - getField("VerticalPosPI").setValue(200,2); - getField("VerticalVelPID").setValue(0.1,0); - getField("VerticalVelPID").setValue(0,1); - getField("VerticalVelPID").setValue(0,2); - getField("VerticalVelPID").setValue(0,3); - getField("MaxRollPitch").setValue(10); - getField("UpdatePeriod").setValue(100); - getField("HorizontalVelMax").setValue(300); - getField("VerticalVelMax").setValue(150); - getField("GuidanceMode").setValue("DUAL_LOOP"); - getField("ThrottleControl").setValue("FALSE"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - GuidanceSettings obj = new GuidanceSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public GuidanceSettings GetInstance(UAVObjectManager objMngr, int instID) - { - return (GuidanceSettings)(objMngr.getObject(GuidanceSettings.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0x6EA79FB4; - protected static final String NAME = "GuidanceSettings"; - protected static String DESCRIPTION = "Settings for the @ref GuidanceModule"; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 1 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java index 3f3b3d8dd..0cd45db1b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java @@ -103,18 +103,17 @@ public class HomeLocation extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java index f56982e69..9d8113846 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java @@ -190,14 +190,6 @@ public class HwSettings extends UAVDataObject { ComUsbBridgeSpeedEnumOptions.add("115200"); fields.add( new UAVObjectField("ComUsbBridgeSpeed", "bps", UAVObjectField.FieldType.ENUM, ComUsbBridgeSpeedElemNames, ComUsbBridgeSpeedEnumOptions) ); - List USB_DeviceTypeElemNames = new ArrayList(); - USB_DeviceTypeElemNames.add("0"); - List USB_DeviceTypeEnumOptions = new ArrayList(); - USB_DeviceTypeEnumOptions.add("HID-only"); - USB_DeviceTypeEnumOptions.add("HID+VCP"); - USB_DeviceTypeEnumOptions.add("VCP-only"); - fields.add( new UAVObjectField("USB_DeviceType", "descriptor", UAVObjectField.FieldType.ENUM, USB_DeviceTypeElemNames, USB_DeviceTypeEnumOptions) ); - List USB_HIDPortElemNames = new ArrayList(); USB_HIDPortElemNames.add("0"); List USB_HIDPortEnumOptions = new ArrayList(); @@ -219,7 +211,12 @@ public class HwSettings extends UAVDataObject { OptionalModulesElemNames.add("ComUsbBridge"); OptionalModulesElemNames.add("Fault"); OptionalModulesElemNames.add("Altitude"); + OptionalModulesElemNames.add("Airspeed"); OptionalModulesElemNames.add("TxPID"); + OptionalModulesElemNames.add("VtolPathFollower"); + OptionalModulesElemNames.add("FixedWingPathFollower"); + OptionalModulesElemNames.add("Battery"); + OptionalModulesElemNames.add("Overo"); List OptionalModulesEnumOptions = new ArrayList(); OptionalModulesEnumOptions.add("Disabled"); OptionalModulesEnumOptions.add("Enabled"); @@ -252,18 +249,17 @@ public class HwSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -286,7 +282,6 @@ public class HwSettings extends UAVDataObject { getField("TelemetrySpeed").setValue("57600"); getField("GPSSpeed").setValue("57600"); getField("ComUsbBridgeSpeed").setValue("57600"); - getField("USB_DeviceType").setValue("HID-only"); getField("USB_HIDPort").setValue("USBTelemetry"); getField("USB_VCPPort").setValue("Disabled"); getField("OptionalModules").setValue("Disabled",0); @@ -295,6 +290,11 @@ public class HwSettings extends UAVDataObject { getField("OptionalModules").setValue("Disabled",3); getField("OptionalModules").setValue("Disabled",4); getField("OptionalModules").setValue("Disabled",5); + getField("OptionalModules").setValue("Disabled",6); + getField("OptionalModules").setValue("Disabled",7); + getField("OptionalModules").setValue("Disabled",8); + getField("OptionalModules").setValue("Disabled",9); + getField("OptionalModules").setValue("Disabled",10); getField("DSMxBind").setValue(0); } @@ -324,7 +324,7 @@ public class HwSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x4730375C; + protected static final int OBJID = 0x5D950E50; protected static final String NAME = "HwSettings"; protected static String DESCRIPTION = "Selection of optional hardware configurations."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java index abd8f41f6..a09e4404d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java @@ -177,18 +177,17 @@ public class I2CStats extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 30000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 30000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java index 6ac5a1b2c..5ce51c245 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java @@ -113,18 +113,17 @@ public class ManualControlCommand extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 2000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 2000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java index c8f460bc4..47ebbc230 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java @@ -51,6 +51,10 @@ public class ManualControlSettings extends UAVDataObject { List fields = new ArrayList(); + List DeadbandElemNames = new ArrayList(); + DeadbandElemNames.add("0"); + fields.add( new UAVObjectField("Deadband", "%", UAVObjectField.FieldType.FLOAT32, DeadbandElemNames, null) ); + List ChannelMinElemNames = new ArrayList(); ChannelMinElemNames.add("Throttle"); ChannelMinElemNames.add("Roll"); @@ -146,6 +150,7 @@ public class ManualControlSettings extends UAVDataObject { Stabilization1SettingsEnumOptions.add("Attitude"); Stabilization1SettingsEnumOptions.add("AxisLock"); Stabilization1SettingsEnumOptions.add("WeakLeveling"); + Stabilization1SettingsEnumOptions.add("VirtualBar"); fields.add( new UAVObjectField("Stabilization1Settings", "", UAVObjectField.FieldType.ENUM, Stabilization1SettingsElemNames, Stabilization1SettingsEnumOptions) ); List Stabilization2SettingsElemNames = new ArrayList(); @@ -158,6 +163,7 @@ public class ManualControlSettings extends UAVDataObject { Stabilization2SettingsEnumOptions.add("Attitude"); Stabilization2SettingsEnumOptions.add("AxisLock"); Stabilization2SettingsEnumOptions.add("WeakLeveling"); + Stabilization2SettingsEnumOptions.add("VirtualBar"); fields.add( new UAVObjectField("Stabilization2Settings", "", UAVObjectField.FieldType.ENUM, Stabilization2SettingsElemNames, Stabilization2SettingsEnumOptions) ); List Stabilization3SettingsElemNames = new ArrayList(); @@ -170,6 +176,7 @@ public class ManualControlSettings extends UAVDataObject { Stabilization3SettingsEnumOptions.add("Attitude"); Stabilization3SettingsEnumOptions.add("AxisLock"); Stabilization3SettingsEnumOptions.add("WeakLeveling"); + Stabilization3SettingsEnumOptions.add("VirtualBar"); fields.add( new UAVObjectField("Stabilization3Settings", "", UAVObjectField.FieldType.ENUM, Stabilization3SettingsElemNames, Stabilization3SettingsEnumOptions) ); List FlightModePositionElemNames = new ArrayList(); @@ -185,8 +192,21 @@ public class ManualControlSettings extends UAVDataObject { FlightModePositionEnumOptions.add("VelocityControl"); FlightModePositionEnumOptions.add("PositionHold"); FlightModePositionEnumOptions.add("PathPlanner"); + FlightModePositionEnumOptions.add("RTH"); + FlightModePositionEnumOptions.add("Land"); fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); + List FlightModeNumberElemNames = new ArrayList(); + FlightModeNumberElemNames.add("0"); + fields.add( new UAVObjectField("FlightModeNumber", "", UAVObjectField.FieldType.UINT8, FlightModeNumberElemNames, null) ); + + List FailsafeBehaviorElemNames = new ArrayList(); + FailsafeBehaviorElemNames.add("0"); + List FailsafeBehaviorEnumOptions = new ArrayList(); + FailsafeBehaviorEnumOptions.add("None"); + FailsafeBehaviorEnumOptions.add("RTH"); + fields.add( new UAVObjectField("FailsafeBehavior", "", UAVObjectField.FieldType.ENUM, FailsafeBehaviorElemNames, FailsafeBehaviorEnumOptions) ); + // Compute the number of bytes for this object int numBytes = 0; @@ -210,18 +230,17 @@ public class ManualControlSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -232,6 +251,7 @@ public class ManualControlSettings extends UAVDataObject { */ public void setDefaultFieldValues() { + getField("Deadband").setValue(0); getField("ChannelMin").setValue(1000,0); getField("ChannelMin").setValue(1000,1); getField("ChannelMin").setValue(1000,2); @@ -291,6 +311,8 @@ public class ManualControlSettings extends UAVDataObject { getField("FlightModePosition").setValue("Manual",0); getField("FlightModePosition").setValue("Stabilized1",1); getField("FlightModePosition").setValue("Stabilized2",2); + getField("FlightModeNumber").setValue(3); + getField("FailsafeBehavior").setValue("None"); } @@ -319,7 +341,7 @@ public class ManualControlSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x59C4551C; + protected static final int OBJID = 0x6C188320; protected static final String NAME = "ManualControlSettings"; protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java index 76841d8ff..094d91545 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java @@ -372,18 +372,17 @@ public class MixerSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java index 80e3b15bf..1f767c5ba 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java @@ -114,18 +114,17 @@ public class MixerStatus extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java index 1629a19d2..6d09a799e 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java @@ -86,18 +86,17 @@ public class NedAccel extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10001; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10001; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java index dccd85d36..42a65e3ab 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java @@ -68,6 +68,7 @@ public class ObjectPersistence extends UAVDataObject { OperationEnumOptions.add("Delete"); OperationEnumOptions.add("FullErase"); OperationEnumOptions.add("Completed"); + OperationEnumOptions.add("Error"); fields.add( new UAVObjectField("Operation", "", UAVObjectField.FieldType.ENUM, OperationElemNames, OperationEnumOptions) ); List SelectionElemNames = new ArrayList(); @@ -102,18 +103,17 @@ public class ObjectPersistence extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -152,7 +152,7 @@ public class ObjectPersistence extends UAVDataObject { } // Constants - protected static final int OBJID = 0xF69AD8B8; + protected static final int OBJID = 0x99C63292; protected static final String NAME = "ObjectPersistence"; protected static String DESCRIPTION = "Someone who knows please enter this"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java index 184098a16..1c87c21c3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java @@ -86,18 +86,17 @@ public class PositionActual extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 1000; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java deleted file mode 100644 index 123ca58af..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java +++ /dev/null @@ -1,147 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner - -generated from positiondesired.xml - **/ -public class PositionDesired extends UAVDataObject { - - public PositionDesired() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List NorthElemNames = new ArrayList(); - NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); - - List EastElemNames = new ArrayList(); - EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); - - List DownElemNames = new ArrayList(); - DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(int instID) { - // TODO: Need to get specific instance to clone - try { - PositionDesired obj = new PositionDesired(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public PositionDesired GetInstance(UAVObjectManager objMngr, int instID) - { - return (PositionDesired)(objMngr.getObject(PositionDesired.OBJID, instID)); - } - - // Constants - protected static final int OBJID = 0x778DBE24; - protected static final String NAME = "PositionDesired"; - protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; - protected static final boolean ISSINGLEINST = 1 == 1; - protected static final boolean ISSETTINGS = 0 == 1; - protected static int NUMBYTES = 0; - - -} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java index ddeacd8d4..51f7faa7d 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java @@ -86,18 +86,17 @@ public class RateDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java index a40b27e38..15391ce71 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java @@ -90,18 +90,17 @@ public class ReceiverActivity extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READONLY; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java index 18cf6f4d6..1a5679d6a 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java @@ -78,18 +78,17 @@ public class SonarAltitude extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java index 32d2c735c..8ca5df722 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java @@ -77,6 +77,7 @@ public class StabilizationDesired extends UAVDataObject { StabilizationModeEnumOptions.add("Attitude"); StabilizationModeEnumOptions.add("AxisLock"); StabilizationModeEnumOptions.add("WeakLeveling"); + StabilizationModeEnumOptions.add("VirtualBar"); fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); @@ -102,18 +103,17 @@ public class StabilizationDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -152,7 +152,7 @@ public class StabilizationDesired extends UAVDataObject { } // Constants - protected static final int OBJID = 0xDB8FFC3C; + protected static final int OBJID = 0xDE1EAAD6; protected static final String NAME = "StabilizationDesired"; protected static String DESCRIPTION = "The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java index ab78bdc74..cc2c69e8f 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java @@ -102,6 +102,31 @@ public class StabilizationSettings extends UAVDataObject { YawPIElemNames.add("ILimit"); fields.add( new UAVObjectField("YawPI", "", UAVObjectField.FieldType.FLOAT32, YawPIElemNames, null) ); + List VbarSensitivityElemNames = new ArrayList(); + VbarSensitivityElemNames.add("Roll"); + VbarSensitivityElemNames.add("Pitch"); + VbarSensitivityElemNames.add("Yaw"); + fields.add( new UAVObjectField("VbarSensitivity", "frac", UAVObjectField.FieldType.FLOAT32, VbarSensitivityElemNames, null) ); + + List VbarRollPIElemNames = new ArrayList(); + VbarRollPIElemNames.add("Kp"); + VbarRollPIElemNames.add("Ki"); + fields.add( new UAVObjectField("VbarRollPI", "1/(deg/s)", UAVObjectField.FieldType.FLOAT32, VbarRollPIElemNames, null) ); + + List VbarPitchPIElemNames = new ArrayList(); + VbarPitchPIElemNames.add("Kp"); + VbarPitchPIElemNames.add("Ki"); + fields.add( new UAVObjectField("VbarPitchPI", "1/(deg/s)", UAVObjectField.FieldType.FLOAT32, VbarPitchPIElemNames, null) ); + + List VbarYawPIElemNames = new ArrayList(); + VbarYawPIElemNames.add("Kp"); + VbarYawPIElemNames.add("Ki"); + fields.add( new UAVObjectField("VbarYawPI", "1/(deg/s)", UAVObjectField.FieldType.FLOAT32, VbarYawPIElemNames, null) ); + + List VbarTauElemNames = new ArrayList(); + VbarTauElemNames.add("0"); + fields.add( new UAVObjectField("VbarTau", "sec", UAVObjectField.FieldType.FLOAT32, VbarTauElemNames, null) ); + List GyroTauElemNames = new ArrayList(); GyroTauElemNames.add("0"); fields.add( new UAVObjectField("GyroTau", "", UAVObjectField.FieldType.FLOAT32, GyroTauElemNames, null) ); @@ -122,6 +147,21 @@ public class StabilizationSettings extends UAVDataObject { YawMaxElemNames.add("0"); fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); + List VbarGyroSuppressElemNames = new ArrayList(); + VbarGyroSuppressElemNames.add("0"); + fields.add( new UAVObjectField("VbarGyroSuppress", "%", UAVObjectField.FieldType.INT8, VbarGyroSuppressElemNames, null) ); + + List VbarPiroCompElemNames = new ArrayList(); + VbarPiroCompElemNames.add("0"); + List VbarPiroCompEnumOptions = new ArrayList(); + VbarPiroCompEnumOptions.add("FALSE"); + VbarPiroCompEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("VbarPiroComp", "", UAVObjectField.FieldType.ENUM, VbarPiroCompElemNames, VbarPiroCompEnumOptions) ); + + List VbarMaxAngleElemNames = new ArrayList(); + VbarMaxAngleElemNames.add("0"); + fields.add( new UAVObjectField("VbarMaxAngle", "deg", UAVObjectField.FieldType.UINT8, VbarMaxAngleElemNames, null) ); + List MaxAxisLockElemNames = new ArrayList(); MaxAxisLockElemNames.add("0"); fields.add( new UAVObjectField("MaxAxisLock", "deg", UAVObjectField.FieldType.UINT8, MaxAxisLockElemNames, null) ); @@ -164,18 +204,17 @@ public class StabilizationSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -213,11 +252,24 @@ public class StabilizationSettings extends UAVDataObject { getField("YawPI").setValue(2,0); getField("YawPI").setValue(0,1); getField("YawPI").setValue(50,2); + getField("VbarSensitivity").setValue(0.5,0); + getField("VbarSensitivity").setValue(0.5,1); + getField("VbarSensitivity").setValue(0.5,2); + getField("VbarRollPI").setValue(0.005,0); + getField("VbarRollPI").setValue(0.002,1); + getField("VbarPitchPI").setValue(0.005,0); + getField("VbarPitchPI").setValue(0.002,1); + getField("VbarYawPI").setValue(0.005,0); + getField("VbarYawPI").setValue(0.002,1); + getField("VbarTau").setValue(0.5); getField("GyroTau").setValue(0.005); getField("WeakLevelingKp").setValue(0.1); getField("RollMax").setValue(55); getField("PitchMax").setValue(55); getField("YawMax").setValue(35); + getField("VbarGyroSuppress").setValue(30); + getField("VbarPiroComp").setValue("FALSE"); + getField("VbarMaxAngle").setValue(10); getField("MaxAxisLock").setValue(15); getField("MaxAxisLockRate").setValue(2); getField("MaxWeakLevelingRate").setValue(5); @@ -250,7 +302,7 @@ public class StabilizationSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x5F78C51E; + protected static final int OBJID = 0xBBC337D4; protected static final String NAME = "StabilizationSettings"; protected static String DESCRIPTION = "PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java index bc4bf0625..3b34763fe 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java @@ -56,7 +56,6 @@ public class SystemAlarms extends UAVDataObject { AlarmElemNames.add("StackOverflow"); AlarmElemNames.add("CPUOverload"); AlarmElemNames.add("EventSystem"); - AlarmElemNames.add("SDCard"); AlarmElemNames.add("Telemetry"); AlarmElemNames.add("ManualControl"); AlarmElemNames.add("Actuator"); @@ -64,12 +63,12 @@ public class SystemAlarms extends UAVDataObject { AlarmElemNames.add("Sensors"); AlarmElemNames.add("Stabilization"); AlarmElemNames.add("Guidance"); - AlarmElemNames.add("AHRSComms"); AlarmElemNames.add("Battery"); AlarmElemNames.add("FlightTime"); AlarmElemNames.add("I2C"); AlarmElemNames.add("GPS"); AlarmElemNames.add("BootFault"); + AlarmElemNames.add("Power"); List AlarmEnumOptions = new ArrayList(); AlarmEnumOptions.add("Uninitialised"); AlarmEnumOptions.add("OK"); @@ -101,18 +100,17 @@ public class SystemAlarms extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } @@ -140,7 +138,6 @@ public class SystemAlarms extends UAVDataObject { getField("Alarm").setValue("Uninitialised",14); getField("Alarm").setValue("Uninitialised",15); getField("Alarm").setValue("Uninitialised",16); - getField("Alarm").setValue("Uninitialised",17); } @@ -169,7 +166,7 @@ public class SystemAlarms extends UAVDataObject { } // Constants - protected static final int OBJID = 0x9C7CBFE; + protected static final int OBJID = 0x737ADCF2; protected static final String NAME = "SystemAlarms"; protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java index e3c2cf0b0..bffbced31 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java @@ -54,6 +54,8 @@ public class SystemSettings extends UAVDataObject { List GUIConfigDataElemNames = new ArrayList(); GUIConfigDataElemNames.add("0"); GUIConfigDataElemNames.add("1"); + GUIConfigDataElemNames.add("2"); + GUIConfigDataElemNames.add("3"); fields.add( new UAVObjectField("GUIConfigData", "bits", UAVObjectField.FieldType.UINT32, GUIConfigDataElemNames, null) ); List AirframeTypeElemNames = new ArrayList(); @@ -75,6 +77,9 @@ public class SystemSettings extends UAVDataObject { AirframeTypeEnumOptions.add("OctoCoaxX"); AirframeTypeEnumOptions.add("HexaCoax"); AirframeTypeEnumOptions.add("Tri"); + AirframeTypeEnumOptions.add("GroundVehicleCar"); + AirframeTypeEnumOptions.add("GroundVehicleDifferential"); + AirframeTypeEnumOptions.add("GroundVehicleMotorcycle"); fields.add( new UAVObjectField("AirframeType", "", UAVObjectField.FieldType.ENUM, AirframeTypeElemNames, AirframeTypeEnumOptions) ); @@ -100,18 +105,17 @@ public class SystemSettings extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.flightTelemetryUpdatePeriod = 0; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_NEVER; - metadata.loggingUpdatePeriod = 0; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + return metadata; } @@ -124,7 +128,9 @@ public class SystemSettings extends UAVDataObject { { getField("GUIConfigData").setValue(0,0); getField("GUIConfigData").setValue(0,1); - getField("AirframeType").setValue("FixedWing"); + getField("GUIConfigData").setValue(0,2); + getField("GUIConfigData").setValue(0,3); + getField("AirframeType").setValue("QuadX"); } @@ -153,7 +159,7 @@ public class SystemSettings extends UAVDataObject { } // Constants - protected static final int OBJID = 0x30BD5D7C; + protected static final int OBJID = 0xC72A326E; protected static final String NAME = "SystemSettings"; protected static String DESCRIPTION = "Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java index 26d01f2a0..888474261 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java @@ -106,18 +106,17 @@ public class SystemStats extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java index eefcef6d9..9f530e6a9 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java @@ -62,11 +62,12 @@ public class TaskInfo extends UAVDataObject { StackRemainingElemNames.add("GPS"); StackRemainingElemNames.add("ManualControl"); StackRemainingElemNames.add("Altitude"); + StackRemainingElemNames.add("Airspeed"); StackRemainingElemNames.add("Stabilization"); StackRemainingElemNames.add("AltitudeHold"); - StackRemainingElemNames.add("Guidance"); - StackRemainingElemNames.add("FlightPlan"); StackRemainingElemNames.add("PathPlanner"); + StackRemainingElemNames.add("PathFollower"); + StackRemainingElemNames.add("FlightPlan"); StackRemainingElemNames.add("Com2UsbBridge"); StackRemainingElemNames.add("Usb2ComBridge"); StackRemainingElemNames.add("OveroSync"); @@ -83,11 +84,12 @@ public class TaskInfo extends UAVDataObject { RunningElemNames.add("GPS"); RunningElemNames.add("ManualControl"); RunningElemNames.add("Altitude"); + RunningElemNames.add("Airspeed"); RunningElemNames.add("Stabilization"); RunningElemNames.add("AltitudeHold"); - RunningElemNames.add("Guidance"); - RunningElemNames.add("FlightPlan"); RunningElemNames.add("PathPlanner"); + RunningElemNames.add("PathFollower"); + RunningElemNames.add("FlightPlan"); RunningElemNames.add("Com2UsbBridge"); RunningElemNames.add("Usb2ComBridge"); RunningElemNames.add("OveroSync"); @@ -107,11 +109,12 @@ public class TaskInfo extends UAVDataObject { RunningTimeElemNames.add("GPS"); RunningTimeElemNames.add("ManualControl"); RunningTimeElemNames.add("Altitude"); + RunningTimeElemNames.add("Airspeed"); RunningTimeElemNames.add("Stabilization"); RunningTimeElemNames.add("AltitudeHold"); - RunningTimeElemNames.add("Guidance"); - RunningTimeElemNames.add("FlightPlan"); RunningTimeElemNames.add("PathPlanner"); + RunningTimeElemNames.add("PathFollower"); + RunningTimeElemNames.add("FlightPlan"); RunningTimeElemNames.add("Com2UsbBridge"); RunningTimeElemNames.add("Usb2ComBridge"); RunningTimeElemNames.add("OveroSync"); @@ -140,18 +143,17 @@ public class TaskInfo extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.TRUE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_ONCHANGE; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.TRUE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 10000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 10000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } @@ -190,7 +192,7 @@ public class TaskInfo extends UAVDataObject { } // Constants - protected static final int OBJID = 0x498F54BA; + protected static final int OBJID = 0xB81CD2AE; protected static final String NAME = "TaskInfo"; protected static String DESCRIPTION = "Task information"; protected static final boolean ISSINGLEINST = 1 == 1; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java index 823643130..7968c37c3 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java @@ -45,11 +45,15 @@ public class UAVObjectsInitialize { objMngr.registerObject( new AltitudeHoldSettings() ); objMngr.registerObject( new AttitudeActual() ); objMngr.registerObject( new AttitudeSettings() ); + objMngr.registerObject( new AttitudeSimulated() ); + objMngr.registerObject( new BaroAirspeed() ); objMngr.registerObject( new BaroAltitude() ); objMngr.registerObject( new CameraDesired() ); objMngr.registerObject( new CameraStabSettings() ); objMngr.registerObject( new FaultSettings() ); objMngr.registerObject( new FirmwareIAPObj() ); + objMngr.registerObject( new FixedWingPathFollowerSettings() ); + objMngr.registerObject( new FixedWingPathFollowerStatus() ); objMngr.registerObject( new FlightBatterySettings() ); objMngr.registerObject( new FlightBatteryState() ); objMngr.registerObject( new FlightPlanControl() ); @@ -61,38 +65,45 @@ public class UAVObjectsInitialize { objMngr.registerObject( new GCSTelemetryStats() ); objMngr.registerObject( new GPSPosition() ); objMngr.registerObject( new GPSSatellites() ); + objMngr.registerObject( new GPSSettings() ); objMngr.registerObject( new GPSTime() ); objMngr.registerObject( new GPSVelocity() ); objMngr.registerObject( new Gyros() ); objMngr.registerObject( new GyrosBias() ); - objMngr.registerObject( new GuidanceSettings() ); objMngr.registerObject( new HomeLocation() ); objMngr.registerObject( new HwSettings() ); objMngr.registerObject( new I2CStats() ); - objMngr.registerObject( new GPSPosition() ); + objMngr.registerObject( new MagBias() ); objMngr.registerObject( new Magnetometer() ); objMngr.registerObject( new ManualControlCommand() ); objMngr.registerObject( new ManualControlSettings() ); objMngr.registerObject( new MixerSettings() ); objMngr.registerObject( new MixerStatus() ); - objMngr.registerObject( new NEDPosition() ); objMngr.registerObject( new NedAccel() ); + objMngr.registerObject( new NEDPosition() ); objMngr.registerObject( new ObjectPersistence() ); + objMngr.registerObject( new OveroSyncSettings() ); + objMngr.registerObject( new OveroSyncStats() ); objMngr.registerObject( new PathDesired() ); + objMngr.registerObject( new PathPlannerSettings() ); + objMngr.registerObject( new PipXSettings() ); + objMngr.registerObject( new PipXStatus() ); objMngr.registerObject( new PositionActual() ); - objMngr.registerObject( new PositionDesired() ); objMngr.registerObject( new RateDesired() ); objMngr.registerObject( new ReceiverActivity() ); + objMngr.registerObject( new RevoCalibration() ); + objMngr.registerObject( new RevoSettings() ); objMngr.registerObject( new SonarAltitude() ); objMngr.registerObject( new StabilizationDesired() ); objMngr.registerObject( new StabilizationSettings() ); objMngr.registerObject( new SystemAlarms() ); objMngr.registerObject( new SystemSettings() ); objMngr.registerObject( new SystemStats() ); - objMngr.registerObject( new TxPIDSettings() ); objMngr.registerObject( new TaskInfo() ); + objMngr.registerObject( new TxPIDSettings() ); objMngr.registerObject( new VelocityActual() ); objMngr.registerObject( new VelocityDesired() ); + objMngr.registerObject( new VtolPathFollowerSettings() ); objMngr.registerObject( new WatchdogStatus() ); objMngr.registerObject( new Waypoint() ); objMngr.registerObject( new WaypointActive() ); diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java index 2a8cd3754..a545bca16 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java @@ -86,18 +86,17 @@ public class VelocityActual extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java index 436ef6448..f506a594c 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java @@ -86,18 +86,17 @@ public class VelocityDesired extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 1000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 1000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + return metadata; } diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java index acbdb43d1..94e85f57b 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java @@ -82,18 +82,17 @@ public class WatchdogStatus extends UAVDataObject { */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.gcsTelemetryAcked = UAVObject.Acked.FALSE; - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_MANUAL; - metadata.gcsTelemetryUpdatePeriod = 0; - - metadata.flightAccess = UAVObject.AccessMode.ACCESS_READWRITE; - metadata.flightTelemetryAcked = UAVObject.Acked.FALSE; - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.flightTelemetryUpdatePeriod = 5000; - - metadata.loggingUpdateMode = UAVObject.UpdateMode.UPDATEMODE_PERIODIC; - metadata.loggingUpdatePeriod = 5000; + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 5000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 5000; + return metadata; } diff --git a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java index 64e2461f5..1283f03cb 100644 --- a/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java +++ b/ground/openpilotgcs/src/libs/juavobjects/templates/uavobjecttemplate.java @@ -74,18 +74,17 @@ $(FIELDSINIT) */ public Metadata getDefaultMetadata() { UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.gcsAccess = UAVObject.AccessMode.$(GCSACCESS); - metadata.gcsTelemetryAcked = UAVObject.Acked.$(GCSTELEM_ACKEDTF); - metadata.gcsTelemetryUpdateMode = UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE); - metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - - metadata.flightAccess = UAVObject.AccessMode.$(FLIGHTACCESS); - metadata.flightTelemetryAcked = UAVObject.Acked.$(FLIGHTTELEM_ACKEDTF); - metadata.flightTelemetryUpdateMode = UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE); - metadata.flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - - metadata.loggingUpdateMode = UAVObject.UpdateMode.$(LOGGING_UPDATEMODE); - metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.$(FLIGHTACCESS)) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.$(GCSACCESS)) << UAVOBJ_GCS_ACCESS_SHIFT | + $(FLIGHTTELEM_ACKED) << UAVOBJ_TELEMETRY_ACKED_SHIFT | + $(GCSTELEM_ACKED) << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.$(FLIGHTTELEM_UPDATEMODE)) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.$(GCSTELEM_UPDATEMODE)) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); + metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); + metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + return metadata; } From 32ec48412d8a2178f7e82be24dfde4bef16c3f89 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 2 Aug 2012 13:08:47 -0500 Subject: [PATCH 253/543] Forgot to initialize the fields for metadata --- androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java index c57b6c2fe..98a3bf8df 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java @@ -27,7 +27,8 @@ public class UAVMetaObject extends UAVObject { modesBitField.add("FlightUpdateOnChange"); modesBitField.add("GCSUpdatePeriodic"); modesBitField.add("GCSUpdateOnChange"); - + + List fields = new ArrayList(); fields.add( new UAVObjectField("Modes", "", UAVObjectField.FieldType.BITFIELD, 1, modesBitField) ); fields.add( new UAVObjectField("Flight Telemetry Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); fields.add( new UAVObjectField("GCS Telemetry Update Period", "ms", UAVObjectField.FieldType.UINT16, 1, null) ); From 95218802daf0b496d71c68359894308de842ba46 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 3 Aug 2012 13:49:16 -0500 Subject: [PATCH 254/543] Catch invalid number decoding to cover cases where there is no IP address. --- .../src/org/openpilot/androidgcs/OPTelemetryService.java | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 1a4b61eb8..917dfb116 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -72,8 +72,14 @@ public class OPTelemetryService extends Service { break; case MSG_CONNECT: terminate = false; + int connection_type; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); - int connection_type = Integer.decode(prefs.getString("connection_type", "")); + try { + connection_type = Integer.decode(prefs.getString("connection_type", "")); + } catch (NumberFormatException e) { + connection_type = 0; + } + switch(connection_type) { case 0: // No connection return; From 65861b4b8d7be00b4ae05c666a65a5a5190c3dca Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 01:35:49 -0500 Subject: [PATCH 255/543] Update the UAVO files --- .../openpilot/uavtalk/uavobjects/Accels.java | 150 ++++++++ .../uavtalk/uavobjects/AltHoldSmoothed.java | 146 ++++++++ .../uavobjects/AltitudeHoldDesired.java | 150 ++++++++ .../uavobjects/AltitudeHoldSettings.java | 169 +++++++++ .../uavtalk/uavobjects/AttitudeSimulated.java | 174 ++++++++++ .../uavtalk/uavobjects/BaroAirspeed.java | 153 ++++++++ .../FixedWingPathFollowerSettings.java | 239 +++++++++++++ .../FixedWingPathFollowerStatus.java | 164 +++++++++ .../uavtalk/uavobjects/GPSSettings.java | 142 ++++++++ .../uavtalk/uavobjects/GPSVelocity.java | 146 ++++++++ .../openpilot/uavtalk/uavobjects/Gyros.java | 150 ++++++++ .../uavtalk/uavobjects/GyrosBias.java | 146 ++++++++ .../openpilot/uavtalk/uavobjects/MagBias.java | 146 ++++++++ .../uavtalk/uavobjects/Magnetometer.java | 146 ++++++++ .../uavtalk/uavobjects/NEDPosition.java | 146 ++++++++ .../uavtalk/uavobjects/OveroSyncSettings.java | 143 ++++++++ .../uavtalk/uavobjects/OveroSyncStats.java | 165 +++++++++ .../uavtalk/uavobjects/PathDesired.java | 162 +++++++++ .../uavobjects/PathPlannerSettings.java | 151 ++++++++ .../uavtalk/uavobjects/PipXSettings.java | 326 ++++++++++++++++++ .../uavtalk/uavobjects/PipXStatus.java | 301 ++++++++++++++++ .../uavtalk/uavobjects/RevoCalibration.java | 249 +++++++++++++ .../uavtalk/uavobjects/RevoSettings.java | 143 ++++++++ .../uavtalk/uavobjects/TxPIDSettings.java | 225 ++++++++++++ .../uavobjects/VtolPathFollowerSettings.java | 232 +++++++++++++ .../uavtalk/uavobjects/Waypoint.java | 159 +++++++++ .../uavtalk/uavobjects/WaypointActive.java | 138 ++++++++ 27 files changed, 4761 insertions(+) create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java create mode 100644 androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java new file mode 100644 index 000000000..32437e63e --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java @@ -0,0 +1,150 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The accel data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The accel data. + +generated from accels.xml + **/ +public class Accels extends UAVDataObject { + + public Accels() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "m/s^2", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "m/s^2", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "m/s^2", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + List temperatureElemNames = new ArrayList(); + temperatureElemNames.add("0"); + fields.add( new UAVObjectField("temperature", "deg C", UAVObjectField.FieldType.FLOAT32, temperatureElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + Accels obj = new Accels(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public Accels GetInstance(UAVObjectManager objMngr, int instID) + { + return (Accels)(objMngr.getObject(Accels.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xDD9D5FC0; + protected static final String NAME = "Accels"; + protected static String DESCRIPTION = "The accel data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java new file mode 100644 index 000000000..46d03a544 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The output on the kalman filter on altitude. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The output on the kalman filter on altitude. + +generated from altholdsmoothed.xml + **/ +public class AltHoldSmoothed extends UAVDataObject { + + public AltHoldSmoothed() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List VelocityElemNames = new ArrayList(); + VelocityElemNames.add("0"); + fields.add( new UAVObjectField("Velocity", "m/s", UAVObjectField.FieldType.FLOAT32, VelocityElemNames, null) ); + + List AccelElemNames = new ArrayList(); + AccelElemNames.add("0"); + fields.add( new UAVObjectField("Accel", "m/s^2", UAVObjectField.FieldType.FLOAT32, AccelElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AltHoldSmoothed obj = new AltHoldSmoothed(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AltHoldSmoothed GetInstance(UAVObjectManager objMngr, int instID) + { + return (AltHoldSmoothed)(objMngr.getObject(AltHoldSmoothed.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x2BC6B9D2; + protected static final String NAME = "AltHoldSmoothed"; + protected static String DESCRIPTION = "The output on the kalman filter on altitude."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java new file mode 100644 index 000000000..efe860340 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java @@ -0,0 +1,150 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Holds the desired altitude (from manual control) as well as the desired attitude to pass through + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Holds the desired altitude (from manual control) as well as the desired attitude to pass through + +generated from altitudeholddesired.xml + **/ +public class AltitudeHoldDesired extends UAVDataObject { + + public AltitudeHoldDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AltitudeElemNames = new ArrayList(); + AltitudeElemNames.add("0"); + fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "deg", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "deg", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "deg/s", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AltitudeHoldDesired obj = new AltitudeHoldDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AltitudeHoldDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (AltitudeHoldDesired)(objMngr.getObject(AltitudeHoldDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x495BAD6E; + protected static final String NAME = "AltitudeHoldDesired"; + protected static String DESCRIPTION = "Holds the desired altitude (from manual control) as well as the desired attitude to pass through"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java new file mode 100644 index 000000000..77b6774b9 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java @@ -0,0 +1,169 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref AltitudeHold module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref AltitudeHold module + +generated from altitudeholdsettings.xml + **/ +public class AltitudeHoldSettings extends UAVDataObject { + + public AltitudeHoldSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List KpElemNames = new ArrayList(); + KpElemNames.add("0"); + fields.add( new UAVObjectField("Kp", "throttle/m", UAVObjectField.FieldType.FLOAT32, KpElemNames, null) ); + + List KiElemNames = new ArrayList(); + KiElemNames.add("0"); + fields.add( new UAVObjectField("Ki", "throttle/m", UAVObjectField.FieldType.FLOAT32, KiElemNames, null) ); + + List KdElemNames = new ArrayList(); + KdElemNames.add("0"); + fields.add( new UAVObjectField("Kd", "throttle/m", UAVObjectField.FieldType.FLOAT32, KdElemNames, null) ); + + List KaElemNames = new ArrayList(); + KaElemNames.add("0"); + fields.add( new UAVObjectField("Ka", "throttle/(m/s^2)", UAVObjectField.FieldType.FLOAT32, KaElemNames, null) ); + + List PressureNoiseElemNames = new ArrayList(); + PressureNoiseElemNames.add("0"); + fields.add( new UAVObjectField("PressureNoise", "m", UAVObjectField.FieldType.FLOAT32, PressureNoiseElemNames, null) ); + + List AccelNoiseElemNames = new ArrayList(); + AccelNoiseElemNames.add("0"); + fields.add( new UAVObjectField("AccelNoise", "m/s^2", UAVObjectField.FieldType.FLOAT32, AccelNoiseElemNames, null) ); + + List AccelDriftElemNames = new ArrayList(); + AccelDriftElemNames.add("0"); + fields.add( new UAVObjectField("AccelDrift", "m/s^2", UAVObjectField.FieldType.FLOAT32, AccelDriftElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("Kp").setValue(0.03); + getField("Ki").setValue(0); + getField("Kd").setValue(0.03); + getField("Ka").setValue(0.005); + getField("PressureNoise").setValue(0.4); + getField("AccelNoise").setValue(5); + getField("AccelDrift").setValue(0.001); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AltitudeHoldSettings obj = new AltitudeHoldSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AltitudeHoldSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (AltitudeHoldSettings)(objMngr.getObject(AltitudeHoldSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xFEC55B42; + protected static final String NAME = "AltitudeHoldSettings"; + protected static String DESCRIPTION = "Settings for the @ref AltitudeHold module"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java new file mode 100644 index 000000000..3a713ab04 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java @@ -0,0 +1,174 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The simulated Attitude estimation from @ref Sensors. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The simulated Attitude estimation from @ref Sensors. + +generated from attitudesimulated.xml + **/ +public class AttitudeSimulated extends UAVDataObject { + + public AttitudeSimulated() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List q1ElemNames = new ArrayList(); + q1ElemNames.add("0"); + fields.add( new UAVObjectField("q1", "", UAVObjectField.FieldType.FLOAT32, q1ElemNames, null) ); + + List q2ElemNames = new ArrayList(); + q2ElemNames.add("0"); + fields.add( new UAVObjectField("q2", "", UAVObjectField.FieldType.FLOAT32, q2ElemNames, null) ); + + List q3ElemNames = new ArrayList(); + q3ElemNames.add("0"); + fields.add( new UAVObjectField("q3", "", UAVObjectField.FieldType.FLOAT32, q3ElemNames, null) ); + + List q4ElemNames = new ArrayList(); + q4ElemNames.add("0"); + fields.add( new UAVObjectField("q4", "", UAVObjectField.FieldType.FLOAT32, q4ElemNames, null) ); + + List RollElemNames = new ArrayList(); + RollElemNames.add("0"); + fields.add( new UAVObjectField("Roll", "degrees", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); + + List PitchElemNames = new ArrayList(); + PitchElemNames.add("0"); + fields.add( new UAVObjectField("Pitch", "degrees", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); + + List YawElemNames = new ArrayList(); + YawElemNames.add("0"); + fields.add( new UAVObjectField("Yaw", "degrees", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); + + List VelocityElemNames = new ArrayList(); + VelocityElemNames.add("North"); + VelocityElemNames.add("East"); + VelocityElemNames.add("Down"); + fields.add( new UAVObjectField("Velocity", "m/s", UAVObjectField.FieldType.FLOAT32, VelocityElemNames, null) ); + + List PositionElemNames = new ArrayList(); + PositionElemNames.add("North"); + PositionElemNames.add("East"); + PositionElemNames.add("Down"); + fields.add( new UAVObjectField("Position", "m", UAVObjectField.FieldType.FLOAT32, PositionElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 100; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + AttitudeSimulated obj = new AttitudeSimulated(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public AttitudeSimulated GetInstance(UAVObjectManager objMngr, int instID) + { + return (AttitudeSimulated)(objMngr.getObject(AttitudeSimulated.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x9266CE74; + protected static final String NAME = "AttitudeSimulated"; + protected static String DESCRIPTION = "The simulated Attitude estimation from @ref Sensors."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java new file mode 100644 index 000000000..439915741 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java @@ -0,0 +1,153 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The raw data from the dynamic pressure sensor with pressure, temperature and airspeed. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The raw data from the dynamic pressure sensor with pressure, temperature and airspeed. + +generated from baroairspeed.xml + **/ +public class BaroAirspeed extends UAVDataObject { + + public BaroAirspeed() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AirspeedElemNames = new ArrayList(); + AirspeedElemNames.add("0"); + fields.add( new UAVObjectField("Airspeed", "m/s", UAVObjectField.FieldType.FLOAT32, AirspeedElemNames, null) ); + + List SensorValueElemNames = new ArrayList(); + SensorValueElemNames.add("0"); + fields.add( new UAVObjectField("SensorValue", "raw", UAVObjectField.FieldType.UINT16, SensorValueElemNames, null) ); + + List ZeroPointElemNames = new ArrayList(); + ZeroPointElemNames.add("0"); + fields.add( new UAVObjectField("ZeroPoint", "raw", UAVObjectField.FieldType.UINT16, ZeroPointElemNames, null) ); + + List ConnectedElemNames = new ArrayList(); + ConnectedElemNames.add("0"); + List ConnectedEnumOptions = new ArrayList(); + ConnectedEnumOptions.add("False"); + ConnectedEnumOptions.add("True"); + fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + BaroAirspeed obj = new BaroAirspeed(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public BaroAirspeed GetInstance(UAVObjectManager objMngr, int instID) + { + return (BaroAirspeed)(objMngr.getObject(BaroAirspeed.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x169EA4A; + protected static final String NAME = "BaroAirspeed"; + protected static String DESCRIPTION = "The raw data from the dynamic pressure sensor with pressure, temperature and airspeed."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java new file mode 100644 index 000000000..00419bc4c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java @@ -0,0 +1,239 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref FixedWingPathFollowerModule + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref FixedWingPathFollowerModule + +generated from fixedwingpathfollowersettings.xml + **/ +public class FixedWingPathFollowerSettings extends UAVDataObject { + + public FixedWingPathFollowerSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List AirSpeedMaxElemNames = new ArrayList(); + AirSpeedMaxElemNames.add("0"); + fields.add( new UAVObjectField("AirSpeedMax", "m/s", UAVObjectField.FieldType.FLOAT32, AirSpeedMaxElemNames, null) ); + + List AirSpeedMinElemNames = new ArrayList(); + AirSpeedMinElemNames.add("0"); + fields.add( new UAVObjectField("AirSpeedMin", "m/s", UAVObjectField.FieldType.FLOAT32, AirSpeedMinElemNames, null) ); + + List VerticalVelMaxElemNames = new ArrayList(); + VerticalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.FLOAT32, VerticalVelMaxElemNames, null) ); + + List HorizontalPosPElemNames = new ArrayList(); + HorizontalPosPElemNames.add("0"); + fields.add( new UAVObjectField("HorizontalPosP", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPElemNames, null) ); + + List VerticalPosPElemNames = new ArrayList(); + VerticalPosPElemNames.add("0"); + fields.add( new UAVObjectField("VerticalPosP", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, VerticalPosPElemNames, null) ); + + List CoursePIElemNames = new ArrayList(); + CoursePIElemNames.add("Kp"); + CoursePIElemNames.add("Ki"); + CoursePIElemNames.add("ILimit"); + fields.add( new UAVObjectField("CoursePI", "deg/deg", UAVObjectField.FieldType.FLOAT32, CoursePIElemNames, null) ); + + List SpeedPElemNames = new ArrayList(); + SpeedPElemNames.add("Kp"); + SpeedPElemNames.add("Max"); + fields.add( new UAVObjectField("SpeedP", "(m/s^2) / ((m/s)/(m/s)", UAVObjectField.FieldType.FLOAT32, SpeedPElemNames, null) ); + + List AccelPIElemNames = new ArrayList(); + AccelPIElemNames.add("Kp"); + AccelPIElemNames.add("Ki"); + AccelPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("AccelPI", "deg / (m/s^2)", UAVObjectField.FieldType.FLOAT32, AccelPIElemNames, null) ); + + List VerticalToPitchCrossFeedElemNames = new ArrayList(); + VerticalToPitchCrossFeedElemNames.add("Kp"); + VerticalToPitchCrossFeedElemNames.add("Max"); + fields.add( new UAVObjectField("VerticalToPitchCrossFeed", "deg / ((m/s)/(m/s))", UAVObjectField.FieldType.FLOAT32, VerticalToPitchCrossFeedElemNames, null) ); + + List AirspeedToVerticalCrossFeedElemNames = new ArrayList(); + AirspeedToVerticalCrossFeedElemNames.add("Kp"); + AirspeedToVerticalCrossFeedElemNames.add("Max"); + fields.add( new UAVObjectField("AirspeedToVerticalCrossFeed", "(m/s) / ((m/s)/(m/s))", UAVObjectField.FieldType.FLOAT32, AirspeedToVerticalCrossFeedElemNames, null) ); + + List PowerPIElemNames = new ArrayList(); + PowerPIElemNames.add("Kp"); + PowerPIElemNames.add("Ki"); + PowerPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("PowerPI", "1/(m/s)", UAVObjectField.FieldType.FLOAT32, PowerPIElemNames, null) ); + + List RollLimitElemNames = new ArrayList(); + RollLimitElemNames.add("Min"); + RollLimitElemNames.add("Neutral"); + RollLimitElemNames.add("Max"); + fields.add( new UAVObjectField("RollLimit", "deg", UAVObjectField.FieldType.FLOAT32, RollLimitElemNames, null) ); + + List PitchLimitElemNames = new ArrayList(); + PitchLimitElemNames.add("Min"); + PitchLimitElemNames.add("Neutral"); + PitchLimitElemNames.add("Max"); + fields.add( new UAVObjectField("PitchLimit", "deg", UAVObjectField.FieldType.FLOAT32, PitchLimitElemNames, null) ); + + List ThrottleLimitElemNames = new ArrayList(); + ThrottleLimitElemNames.add("Min"); + ThrottleLimitElemNames.add("Neutral"); + ThrottleLimitElemNames.add("Max"); + fields.add( new UAVObjectField("ThrottleLimit", "", UAVObjectField.FieldType.FLOAT32, ThrottleLimitElemNames, null) ); + + List UpdatePeriodElemNames = new ArrayList(); + UpdatePeriodElemNames.add("0"); + fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("AirSpeedMax").setValue(15); + getField("AirSpeedMin").setValue(10); + getField("VerticalVelMax").setValue(10); + getField("HorizontalPosP").setValue(0.05); + getField("VerticalPosP").setValue(0.05); + getField("CoursePI").setValue(0.2,0); + getField("CoursePI").setValue(0,1); + getField("CoursePI").setValue(0,2); + getField("SpeedP").setValue(10,0); + getField("SpeedP").setValue(10,1); + getField("AccelPI").setValue(1.5,0); + getField("AccelPI").setValue(1.5,1); + getField("AccelPI").setValue(20,2); + getField("VerticalToPitchCrossFeed").setValue(50,0); + getField("VerticalToPitchCrossFeed").setValue(5,1); + getField("AirspeedToVerticalCrossFeed").setValue(100,0); + getField("AirspeedToVerticalCrossFeed").setValue(100,1); + getField("PowerPI").setValue(0.01,0); + getField("PowerPI").setValue(0.01,1); + getField("PowerPI").setValue(0.8,2); + getField("RollLimit").setValue(-35,0); + getField("RollLimit").setValue(0,1); + getField("RollLimit").setValue(35,2); + getField("PitchLimit").setValue(-10,0); + getField("PitchLimit").setValue(5,1); + getField("PitchLimit").setValue(20,2); + getField("ThrottleLimit").setValue(0.1,0); + getField("ThrottleLimit").setValue(0.5,1); + getField("ThrottleLimit").setValue(0.9,2); + getField("UpdatePeriod").setValue(100); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FixedWingPathFollowerSettings obj = new FixedWingPathFollowerSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FixedWingPathFollowerSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (FixedWingPathFollowerSettings)(objMngr.getObject(FixedWingPathFollowerSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x8A3F1E02; + protected static final String NAME = "FixedWingPathFollowerSettings"; + protected static String DESCRIPTION = "Settings for the @ref FixedWingPathFollowerModule"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java new file mode 100644 index 000000000..a40be35cf --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java @@ -0,0 +1,164 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Object Storing Debugging Information on PID internals + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Object Storing Debugging Information on PID internals + +generated from fixedwingpathfollowerstatus.xml + **/ +public class FixedWingPathFollowerStatus extends UAVDataObject { + + public FixedWingPathFollowerStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List EElemNames = new ArrayList(); + EElemNames.add("Course"); + EElemNames.add("Speed"); + EElemNames.add("Accel"); + EElemNames.add("Power"); + fields.add( new UAVObjectField("E", "", UAVObjectField.FieldType.FLOAT32, EElemNames, null) ); + + List AElemNames = new ArrayList(); + AElemNames.add("Course"); + AElemNames.add("Speed"); + AElemNames.add("Accel"); + AElemNames.add("Power"); + fields.add( new UAVObjectField("A", "", UAVObjectField.FieldType.FLOAT32, AElemNames, null) ); + + List CElemNames = new ArrayList(); + CElemNames.add("Course"); + CElemNames.add("Speed"); + CElemNames.add("Accel"); + CElemNames.add("Power"); + fields.add( new UAVObjectField("C", "", UAVObjectField.FieldType.FLOAT32, CElemNames, null) ); + + List ErrorsElemNames = new ArrayList(); + ErrorsElemNames.add("Wind"); + ErrorsElemNames.add("Lowspeed"); + ErrorsElemNames.add("Highspeed"); + ErrorsElemNames.add("Lowpower"); + ErrorsElemNames.add("Highpower"); + ErrorsElemNames.add("Pitchcontrol"); + fields.add( new UAVObjectField("Errors", "", UAVObjectField.FieldType.UINT8, ErrorsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 500; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + FixedWingPathFollowerStatus obj = new FixedWingPathFollowerStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public FixedWingPathFollowerStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (FixedWingPathFollowerStatus)(objMngr.getObject(FixedWingPathFollowerStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA0D6F6D4; + protected static final String NAME = "FixedWingPathFollowerStatus"; + protected static String DESCRIPTION = "Object Storing Debugging Information on PID internals"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java new file mode 100644 index 000000000..f534fc89c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java @@ -0,0 +1,142 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the GPS + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the GPS + +generated from gpssettings.xml + **/ +public class GPSSettings extends UAVDataObject { + + public GPSSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List DataProtocolElemNames = new ArrayList(); + DataProtocolElemNames.add("0"); + List DataProtocolEnumOptions = new ArrayList(); + DataProtocolEnumOptions.add("NMEA"); + DataProtocolEnumOptions.add("UBX"); + fields.add( new UAVObjectField("DataProtocol", "", UAVObjectField.FieldType.ENUM, DataProtocolElemNames, DataProtocolEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("DataProtocol").setValue("NMEA"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSSettings obj = new GPSSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSSettings)(objMngr.getObject(GPSSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xAC5F6370; + protected static final String NAME = "GPSSettings"; + protected static String DESCRIPTION = "Settings for the GPS"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java new file mode 100644 index 000000000..2ce4a3c62 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Raw GPS data from @ref GPSModule. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Raw GPS data from @ref GPSModule. + +generated from gpsvelocity.xml + **/ +public class GPSVelocity extends UAVDataObject { + + public GPSVelocity() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "m/s", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "m/s", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "m/s", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GPSVelocity obj = new GPSVelocity(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GPSVelocity GetInstance(UAVObjectManager objMngr, int instID) + { + return (GPSVelocity)(objMngr.getObject(GPSVelocity.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x8245DC80; + protected static final String NAME = "GPSVelocity"; + protected static String DESCRIPTION = "Raw GPS data from @ref GPSModule."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java new file mode 100644 index 000000000..5c960d2e6 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java @@ -0,0 +1,150 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The gyro data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The gyro data. + +generated from gyros.xml + **/ +public class Gyros extends UAVDataObject { + + public Gyros() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "deg/s", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "deg/s", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "deg/s", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + List temperatureElemNames = new ArrayList(); + temperatureElemNames.add("0"); + fields.add( new UAVObjectField("temperature", "deg C", UAVObjectField.FieldType.FLOAT32, temperatureElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + Gyros obj = new Gyros(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public Gyros GetInstance(UAVObjectManager objMngr, int instID) + { + return (Gyros)(objMngr.getObject(Gyros.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x4228AF6; + protected static final String NAME = "Gyros"; + protected static String DESCRIPTION = "The gyro data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java new file mode 100644 index 000000000..00bc7da2d --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The gyro data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The gyro data. + +generated from gyrosbias.xml + **/ +public class GyrosBias extends UAVDataObject { + + public GyrosBias() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "deg/s", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "deg/s", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "deg/s", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + GyrosBias obj = new GyrosBias(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public GyrosBias GetInstance(UAVObjectManager objMngr, int instID) + { + return (GyrosBias)(objMngr.getObject(GyrosBias.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE4B6F980; + protected static final String NAME = "GyrosBias"; + protected static String DESCRIPTION = "The gyro data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java new file mode 100644 index 000000000..398f455d5 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The gyro data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The gyro data. + +generated from magbias.xml + **/ +public class MagBias extends UAVDataObject { + + public MagBias() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "mGau", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "mGau", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "mGau", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + MagBias obj = new MagBias(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public MagBias GetInstance(UAVObjectManager objMngr, int instID) + { + return (MagBias)(objMngr.getObject(MagBias.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x5043E510; + protected static final String NAME = "MagBias"; + protected static String DESCRIPTION = "The gyro data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java new file mode 100644 index 000000000..583817cca --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The mag data. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The mag data. + +generated from magnetometer.xml + **/ +public class Magnetometer extends UAVDataObject { + + public Magnetometer() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List xElemNames = new ArrayList(); + xElemNames.add("0"); + fields.add( new UAVObjectField("x", "mGa", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); + + List yElemNames = new ArrayList(); + yElemNames.add("0"); + fields.add( new UAVObjectField("y", "mGa", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); + + List zElemNames = new ArrayList(); + zElemNames.add("0"); + fields.add( new UAVObjectField("z", "mGa", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + Magnetometer obj = new Magnetometer(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public Magnetometer GetInstance(UAVObjectManager objMngr, int instID) + { + return (Magnetometer)(objMngr.getObject(Magnetometer.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x813B55DE; + protected static final String NAME = "Magnetometer"; + protected static String DESCRIPTION = "The mag data."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java new file mode 100644 index 000000000..0aa67862e --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java @@ -0,0 +1,146 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Contains the current position relative to @ref HomeLocation + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Contains the current position relative to @ref HomeLocation + +generated from nedposition.xml + **/ +public class NEDPosition extends UAVDataObject { + + public NEDPosition() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List NorthElemNames = new ArrayList(); + NorthElemNames.add("0"); + fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); + + List EastElemNames = new ArrayList(); + EastElemNames.add("0"); + fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); + + List DownElemNames = new ArrayList(); + DownElemNames.add("0"); + fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + NEDPosition obj = new NEDPosition(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public NEDPosition GetInstance(UAVObjectManager objMngr, int instID) + { + return (NEDPosition)(objMngr.getObject(NEDPosition.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1FB15A00; + protected static final String NAME = "NEDPosition"; + protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java new file mode 100644 index 000000000..c680d230c --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java @@ -0,0 +1,143 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings to control the behavior of the overo sync module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings to control the behavior of the overo sync module + +generated from overosyncsettings.xml + **/ +public class OveroSyncSettings extends UAVDataObject { + + public OveroSyncSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List LogOnElemNames = new ArrayList(); + LogOnElemNames.add("0"); + List LogOnEnumOptions = new ArrayList(); + LogOnEnumOptions.add("Never"); + LogOnEnumOptions.add("Always"); + LogOnEnumOptions.add("Armed"); + fields.add( new UAVObjectField("LogOn", "", UAVObjectField.FieldType.ENUM, LogOnElemNames, LogOnEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("LogOn").setValue("Armed"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + OveroSyncSettings obj = new OveroSyncSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public OveroSyncSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (OveroSyncSettings)(objMngr.getObject(OveroSyncSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA1ABC278; + protected static final String NAME = "OveroSyncSettings"; + protected static String DESCRIPTION = "Settings to control the behavior of the overo sync module"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java new file mode 100644 index 000000000..4c31f21dd --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java @@ -0,0 +1,165 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Maintains statistics on transfer rate to and from over + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Maintains statistics on transfer rate to and from over + +generated from overosyncstats.xml + **/ +public class OveroSyncStats extends UAVDataObject { + + public OveroSyncStats() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List SendElemNames = new ArrayList(); + SendElemNames.add("0"); + fields.add( new UAVObjectField("Send", "B/s", UAVObjectField.FieldType.UINT32, SendElemNames, null) ); + + List ReceivedElemNames = new ArrayList(); + ReceivedElemNames.add("0"); + fields.add( new UAVObjectField("Received", "B/s", UAVObjectField.FieldType.UINT32, ReceivedElemNames, null) ); + + List FramesyncErrorsElemNames = new ArrayList(); + FramesyncErrorsElemNames.add("0"); + fields.add( new UAVObjectField("FramesyncErrors", "count", UAVObjectField.FieldType.UINT32, FramesyncErrorsElemNames, null) ); + + List UnderrunErrorsElemNames = new ArrayList(); + UnderrunErrorsElemNames.add("0"); + fields.add( new UAVObjectField("UnderrunErrors", "count", UAVObjectField.FieldType.UINT32, UnderrunErrorsElemNames, null) ); + + List DroppedUpdatesElemNames = new ArrayList(); + DroppedUpdatesElemNames.add("0"); + fields.add( new UAVObjectField("DroppedUpdates", "", UAVObjectField.FieldType.UINT32, DroppedUpdatesElemNames, null) ); + + List PacketsElemNames = new ArrayList(); + PacketsElemNames.add("0"); + fields.add( new UAVObjectField("Packets", "", UAVObjectField.FieldType.UINT32, PacketsElemNames, null) ); + + List ConnectedElemNames = new ArrayList(); + ConnectedElemNames.add("0"); + List ConnectedEnumOptions = new ArrayList(); + ConnectedEnumOptions.add("False"); + ConnectedEnumOptions.add("True"); + fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + OveroSyncStats obj = new OveroSyncStats(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public OveroSyncStats GetInstance(UAVObjectManager objMngr, int instID) + { + return (OveroSyncStats)(objMngr.getObject(OveroSyncStats.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xD2085FAC; + protected static final String NAME = "OveroSyncStats"; + protected static String DESCRIPTION = "Maintains statistics on transfer rate to and from over"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java new file mode 100644 index 000000000..38e710477 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java @@ -0,0 +1,162 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner + +generated from pathdesired.xml + **/ +public class PathDesired extends UAVDataObject { + + public PathDesired() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List StartElemNames = new ArrayList(); + StartElemNames.add("North"); + StartElemNames.add("East"); + StartElemNames.add("Down"); + fields.add( new UAVObjectField("Start", "m", UAVObjectField.FieldType.FLOAT32, StartElemNames, null) ); + + List EndElemNames = new ArrayList(); + EndElemNames.add("North"); + EndElemNames.add("East"); + EndElemNames.add("Down"); + fields.add( new UAVObjectField("End", "m", UAVObjectField.FieldType.FLOAT32, EndElemNames, null) ); + + List StartingVelocityElemNames = new ArrayList(); + StartingVelocityElemNames.add("0"); + fields.add( new UAVObjectField("StartingVelocity", "m/s", UAVObjectField.FieldType.FLOAT32, StartingVelocityElemNames, null) ); + + List EndingVelocityElemNames = new ArrayList(); + EndingVelocityElemNames.add("0"); + fields.add( new UAVObjectField("EndingVelocity", "m/s", UAVObjectField.FieldType.FLOAT32, EndingVelocityElemNames, null) ); + + List ModeElemNames = new ArrayList(); + ModeElemNames.add("0"); + List ModeEnumOptions = new ArrayList(); + ModeEnumOptions.add("Endpoint"); + ModeEnumOptions.add("Path"); + ModeEnumOptions.add("Land"); + fields.add( new UAVObjectField("Mode", "", UAVObjectField.FieldType.ENUM, ModeElemNames, ModeEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 1000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PathDesired obj = new PathDesired(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PathDesired GetInstance(UAVObjectManager objMngr, int instID) + { + return (PathDesired)(objMngr.getObject(PathDesired.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x5A4DC71A; + protected static final String NAME = "PathDesired"; + protected static String DESCRIPTION = "The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner "; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java new file mode 100644 index 000000000..fb6b66e19 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java @@ -0,0 +1,151 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref PathPlanner Module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref PathPlanner Module + +generated from pathplannersettings.xml + **/ +public class PathPlannerSettings extends UAVDataObject { + + public PathPlannerSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List PathModeElemNames = new ArrayList(); + PathModeElemNames.add("0"); + List PathModeEnumOptions = new ArrayList(); + PathModeEnumOptions.add("ENDPOINT"); + PathModeEnumOptions.add("PATH"); + fields.add( new UAVObjectField("PathMode", "", UAVObjectField.FieldType.ENUM, PathModeElemNames, PathModeEnumOptions) ); + + List PreprogrammedPathElemNames = new ArrayList(); + PreprogrammedPathElemNames.add("0"); + List PreprogrammedPathEnumOptions = new ArrayList(); + PreprogrammedPathEnumOptions.add("NONE"); + PreprogrammedPathEnumOptions.add("10M_BOX"); + PreprogrammedPathEnumOptions.add("LOGO"); + fields.add( new UAVObjectField("PreprogrammedPath", "", UAVObjectField.FieldType.ENUM, PreprogrammedPathElemNames, PreprogrammedPathEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("PathMode").setValue("PATH"); + getField("PreprogrammedPath").setValue("NONE"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PathPlannerSettings obj = new PathPlannerSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PathPlannerSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (PathPlannerSettings)(objMngr.getObject(PathPlannerSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x290E45DA; + protected static final String NAME = "PathPlannerSettings"; + protected static String DESCRIPTION = "Settings for the @ref PathPlanner Module"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java new file mode 100644 index 000000000..aa5387148 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java @@ -0,0 +1,326 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * PipXtreme configurations options. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +PipXtreme configurations options. + +generated from pipxsettings.xml + **/ +public class PipXSettings extends UAVDataObject { + + public PipXSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List PairIDElemNames = new ArrayList(); + PairIDElemNames.add("0"); + fields.add( new UAVObjectField("PairID", "", UAVObjectField.FieldType.UINT32, PairIDElemNames, null) ); + + List FrequencyElemNames = new ArrayList(); + FrequencyElemNames.add("0"); + fields.add( new UAVObjectField("Frequency", "", UAVObjectField.FieldType.UINT32, FrequencyElemNames, null) ); + + List SendTimeoutElemNames = new ArrayList(); + SendTimeoutElemNames.add("0"); + fields.add( new UAVObjectField("SendTimeout", "ms", UAVObjectField.FieldType.UINT16, SendTimeoutElemNames, null) ); + + List TelemetryConfigElemNames = new ArrayList(); + TelemetryConfigElemNames.add("0"); + List TelemetryConfigEnumOptions = new ArrayList(); + TelemetryConfigEnumOptions.add("Disabled"); + TelemetryConfigEnumOptions.add("Serial"); + TelemetryConfigEnumOptions.add("UAVTalk"); + TelemetryConfigEnumOptions.add("GCS"); + TelemetryConfigEnumOptions.add("Debug"); + fields.add( new UAVObjectField("TelemetryConfig", "function", UAVObjectField.FieldType.ENUM, TelemetryConfigElemNames, TelemetryConfigEnumOptions) ); + + List TelemetrySpeedElemNames = new ArrayList(); + TelemetrySpeedElemNames.add("0"); + List TelemetrySpeedEnumOptions = new ArrayList(); + TelemetrySpeedEnumOptions.add("2400"); + TelemetrySpeedEnumOptions.add("4800"); + TelemetrySpeedEnumOptions.add("9600"); + TelemetrySpeedEnumOptions.add("19200"); + TelemetrySpeedEnumOptions.add("38400"); + TelemetrySpeedEnumOptions.add("57600"); + TelemetrySpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("TelemetrySpeed", "bps", UAVObjectField.FieldType.ENUM, TelemetrySpeedElemNames, TelemetrySpeedEnumOptions) ); + + List FlexiConfigElemNames = new ArrayList(); + FlexiConfigElemNames.add("0"); + List FlexiConfigEnumOptions = new ArrayList(); + FlexiConfigEnumOptions.add("Disabled"); + FlexiConfigEnumOptions.add("Serial"); + FlexiConfigEnumOptions.add("UAVTalk"); + FlexiConfigEnumOptions.add("GCS"); + FlexiConfigEnumOptions.add("PPM_In"); + FlexiConfigEnumOptions.add("PPM_Out"); + FlexiConfigEnumOptions.add("RSSI"); + FlexiConfigEnumOptions.add("Debug"); + fields.add( new UAVObjectField("FlexiConfig", "function", UAVObjectField.FieldType.ENUM, FlexiConfigElemNames, FlexiConfigEnumOptions) ); + + List FlexiSpeedElemNames = new ArrayList(); + FlexiSpeedElemNames.add("0"); + List FlexiSpeedEnumOptions = new ArrayList(); + FlexiSpeedEnumOptions.add("2400"); + FlexiSpeedEnumOptions.add("4800"); + FlexiSpeedEnumOptions.add("9600"); + FlexiSpeedEnumOptions.add("19200"); + FlexiSpeedEnumOptions.add("38400"); + FlexiSpeedEnumOptions.add("57600"); + FlexiSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("FlexiSpeed", "bps", UAVObjectField.FieldType.ENUM, FlexiSpeedElemNames, FlexiSpeedEnumOptions) ); + + List VCPConfigElemNames = new ArrayList(); + VCPConfigElemNames.add("0"); + List VCPConfigEnumOptions = new ArrayList(); + VCPConfigEnumOptions.add("Disabled"); + VCPConfigEnumOptions.add("Serial"); + VCPConfigEnumOptions.add("Debug"); + fields.add( new UAVObjectField("VCPConfig", "function", UAVObjectField.FieldType.ENUM, VCPConfigElemNames, VCPConfigEnumOptions) ); + + List VCPSpeedElemNames = new ArrayList(); + VCPSpeedElemNames.add("0"); + List VCPSpeedEnumOptions = new ArrayList(); + VCPSpeedEnumOptions.add("2400"); + VCPSpeedEnumOptions.add("4800"); + VCPSpeedEnumOptions.add("9600"); + VCPSpeedEnumOptions.add("19200"); + VCPSpeedEnumOptions.add("38400"); + VCPSpeedEnumOptions.add("57600"); + VCPSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("VCPSpeed", "bps", UAVObjectField.FieldType.ENUM, VCPSpeedElemNames, VCPSpeedEnumOptions) ); + + List RFSpeedElemNames = new ArrayList(); + RFSpeedElemNames.add("0"); + List RFSpeedEnumOptions = new ArrayList(); + RFSpeedEnumOptions.add("2400"); + RFSpeedEnumOptions.add("4800"); + RFSpeedEnumOptions.add("9600"); + RFSpeedEnumOptions.add("19200"); + RFSpeedEnumOptions.add("38400"); + RFSpeedEnumOptions.add("57600"); + RFSpeedEnumOptions.add("115200"); + fields.add( new UAVObjectField("RFSpeed", "bps", UAVObjectField.FieldType.ENUM, RFSpeedElemNames, RFSpeedEnumOptions) ); + + List MaxRFPowerElemNames = new ArrayList(); + MaxRFPowerElemNames.add("0"); + List MaxRFPowerEnumOptions = new ArrayList(); + MaxRFPowerEnumOptions.add("1.25"); + MaxRFPowerEnumOptions.add("1.6"); + MaxRFPowerEnumOptions.add("3.16"); + MaxRFPowerEnumOptions.add("6.3"); + MaxRFPowerEnumOptions.add("12.6"); + MaxRFPowerEnumOptions.add("25"); + MaxRFPowerEnumOptions.add("50"); + MaxRFPowerEnumOptions.add("100"); + fields.add( new UAVObjectField("MaxRFPower", "mW", UAVObjectField.FieldType.ENUM, MaxRFPowerElemNames, MaxRFPowerEnumOptions) ); + + List MinPacketSizeElemNames = new ArrayList(); + MinPacketSizeElemNames.add("0"); + fields.add( new UAVObjectField("MinPacketSize", "bytes", UAVObjectField.FieldType.UINT8, MinPacketSizeElemNames, null) ); + + List FrequencyCalibrationElemNames = new ArrayList(); + FrequencyCalibrationElemNames.add("0"); + fields.add( new UAVObjectField("FrequencyCalibration", "", UAVObjectField.FieldType.UINT8, FrequencyCalibrationElemNames, null) ); + + List AESKeyElemNames = new ArrayList(); + AESKeyElemNames.add("0"); + AESKeyElemNames.add("1"); + AESKeyElemNames.add("2"); + AESKeyElemNames.add("3"); + AESKeyElemNames.add("4"); + AESKeyElemNames.add("5"); + AESKeyElemNames.add("6"); + AESKeyElemNames.add("7"); + AESKeyElemNames.add("8"); + AESKeyElemNames.add("9"); + AESKeyElemNames.add("10"); + AESKeyElemNames.add("11"); + AESKeyElemNames.add("12"); + AESKeyElemNames.add("13"); + AESKeyElemNames.add("14"); + AESKeyElemNames.add("15"); + AESKeyElemNames.add("16"); + AESKeyElemNames.add("17"); + AESKeyElemNames.add("18"); + AESKeyElemNames.add("19"); + AESKeyElemNames.add("20"); + AESKeyElemNames.add("21"); + AESKeyElemNames.add("22"); + AESKeyElemNames.add("23"); + AESKeyElemNames.add("24"); + AESKeyElemNames.add("25"); + AESKeyElemNames.add("26"); + AESKeyElemNames.add("27"); + AESKeyElemNames.add("28"); + AESKeyElemNames.add("29"); + AESKeyElemNames.add("30"); + AESKeyElemNames.add("31"); + fields.add( new UAVObjectField("AESKey", "", UAVObjectField.FieldType.UINT8, AESKeyElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("PairID").setValue(0); + getField("Frequency").setValue(434000000); + getField("SendTimeout").setValue(50); + getField("TelemetryConfig").setValue("UAVTalk"); + getField("TelemetrySpeed").setValue("57600"); + getField("FlexiConfig").setValue("Disabled"); + getField("FlexiSpeed").setValue("57600"); + getField("VCPConfig").setValue("Disabled"); + getField("VCPSpeed").setValue("57600"); + getField("RFSpeed").setValue("115200"); + getField("MaxRFPower").setValue("100"); + getField("MinPacketSize").setValue(50); + getField("FrequencyCalibration").setValue(127); + getField("AESKey").setValue(0,0); + getField("AESKey").setValue(0,1); + getField("AESKey").setValue(0,2); + getField("AESKey").setValue(0,3); + getField("AESKey").setValue(0,4); + getField("AESKey").setValue(0,5); + getField("AESKey").setValue(0,6); + getField("AESKey").setValue(0,7); + getField("AESKey").setValue(0,8); + getField("AESKey").setValue(0,9); + getField("AESKey").setValue(0,10); + getField("AESKey").setValue(0,11); + getField("AESKey").setValue(0,12); + getField("AESKey").setValue(0,13); + getField("AESKey").setValue(0,14); + getField("AESKey").setValue(0,15); + getField("AESKey").setValue(0,16); + getField("AESKey").setValue(0,17); + getField("AESKey").setValue(0,18); + getField("AESKey").setValue(0,19); + getField("AESKey").setValue(0,20); + getField("AESKey").setValue(0,21); + getField("AESKey").setValue(0,22); + getField("AESKey").setValue(0,23); + getField("AESKey").setValue(0,24); + getField("AESKey").setValue(0,25); + getField("AESKey").setValue(0,26); + getField("AESKey").setValue(0,27); + getField("AESKey").setValue(0,28); + getField("AESKey").setValue(0,29); + getField("AESKey").setValue(0,30); + getField("AESKey").setValue(0,31); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PipXSettings obj = new PipXSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PipXSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (PipXSettings)(objMngr.getObject(PipXSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xBA192BCA; + protected static final String NAME = "PipXSettings"; + protected static String DESCRIPTION = "PipXtreme configurations options."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java new file mode 100644 index 000000000..fb6a91e33 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java @@ -0,0 +1,301 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * PipXtreme device status. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +PipXtreme device status. + +generated from pipxstatus.xml + **/ +public class PipXStatus extends UAVDataObject { + + public PipXStatus() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List MinFrequencyElemNames = new ArrayList(); + MinFrequencyElemNames.add("0"); + fields.add( new UAVObjectField("MinFrequency", "Hz", UAVObjectField.FieldType.UINT32, MinFrequencyElemNames, null) ); + + List MaxFrequencyElemNames = new ArrayList(); + MaxFrequencyElemNames.add("0"); + fields.add( new UAVObjectField("MaxFrequency", "Hz", UAVObjectField.FieldType.UINT32, MaxFrequencyElemNames, null) ); + + List FrequencyStepSizeElemNames = new ArrayList(); + FrequencyStepSizeElemNames.add("0"); + fields.add( new UAVObjectField("FrequencyStepSize", "", UAVObjectField.FieldType.FLOAT32, FrequencyStepSizeElemNames, null) ); + + List DeviceIDElemNames = new ArrayList(); + DeviceIDElemNames.add("0"); + fields.add( new UAVObjectField("DeviceID", "", UAVObjectField.FieldType.UINT32, DeviceIDElemNames, null) ); + + List AFCElemNames = new ArrayList(); + AFCElemNames.add("0"); + fields.add( new UAVObjectField("AFC", "", UAVObjectField.FieldType.INT32, AFCElemNames, null) ); + + List PairIDsElemNames = new ArrayList(); + PairIDsElemNames.add("0"); + PairIDsElemNames.add("1"); + PairIDsElemNames.add("2"); + PairIDsElemNames.add("3"); + fields.add( new UAVObjectField("PairIDs", "", UAVObjectField.FieldType.UINT32, PairIDsElemNames, null) ); + + List BoardRevisionElemNames = new ArrayList(); + BoardRevisionElemNames.add("0"); + fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); + + List RetriesElemNames = new ArrayList(); + RetriesElemNames.add("0"); + fields.add( new UAVObjectField("Retries", "", UAVObjectField.FieldType.UINT16, RetriesElemNames, null) ); + + List ErrorsElemNames = new ArrayList(); + ErrorsElemNames.add("0"); + fields.add( new UAVObjectField("Errors", "", UAVObjectField.FieldType.UINT16, ErrorsElemNames, null) ); + + List UAVTalkErrorsElemNames = new ArrayList(); + UAVTalkErrorsElemNames.add("0"); + fields.add( new UAVObjectField("UAVTalkErrors", "", UAVObjectField.FieldType.UINT16, UAVTalkErrorsElemNames, null) ); + + List DroppedElemNames = new ArrayList(); + DroppedElemNames.add("0"); + fields.add( new UAVObjectField("Dropped", "", UAVObjectField.FieldType.UINT16, DroppedElemNames, null) ); + + List ResetsElemNames = new ArrayList(); + ResetsElemNames.add("0"); + fields.add( new UAVObjectField("Resets", "", UAVObjectField.FieldType.UINT16, ResetsElemNames, null) ); + + List TXRateElemNames = new ArrayList(); + TXRateElemNames.add("0"); + fields.add( new UAVObjectField("TXRate", "Bps", UAVObjectField.FieldType.UINT16, TXRateElemNames, null) ); + + List RXRateElemNames = new ArrayList(); + RXRateElemNames.add("0"); + fields.add( new UAVObjectField("RXRate", "Bps", UAVObjectField.FieldType.UINT16, RXRateElemNames, null) ); + + List DescriptionElemNames = new ArrayList(); + DescriptionElemNames.add("0"); + DescriptionElemNames.add("1"); + DescriptionElemNames.add("2"); + DescriptionElemNames.add("3"); + DescriptionElemNames.add("4"); + DescriptionElemNames.add("5"); + DescriptionElemNames.add("6"); + DescriptionElemNames.add("7"); + DescriptionElemNames.add("8"); + DescriptionElemNames.add("9"); + DescriptionElemNames.add("10"); + DescriptionElemNames.add("11"); + DescriptionElemNames.add("12"); + DescriptionElemNames.add("13"); + DescriptionElemNames.add("14"); + DescriptionElemNames.add("15"); + DescriptionElemNames.add("16"); + DescriptionElemNames.add("17"); + DescriptionElemNames.add("18"); + DescriptionElemNames.add("19"); + DescriptionElemNames.add("20"); + DescriptionElemNames.add("21"); + DescriptionElemNames.add("22"); + DescriptionElemNames.add("23"); + DescriptionElemNames.add("24"); + DescriptionElemNames.add("25"); + DescriptionElemNames.add("26"); + DescriptionElemNames.add("27"); + DescriptionElemNames.add("28"); + DescriptionElemNames.add("29"); + DescriptionElemNames.add("30"); + DescriptionElemNames.add("31"); + DescriptionElemNames.add("32"); + DescriptionElemNames.add("33"); + DescriptionElemNames.add("34"); + DescriptionElemNames.add("35"); + DescriptionElemNames.add("36"); + DescriptionElemNames.add("37"); + DescriptionElemNames.add("38"); + DescriptionElemNames.add("39"); + fields.add( new UAVObjectField("Description", "", UAVObjectField.FieldType.UINT8, DescriptionElemNames, null) ); + + List CPUSerialElemNames = new ArrayList(); + CPUSerialElemNames.add("0"); + CPUSerialElemNames.add("1"); + CPUSerialElemNames.add("2"); + CPUSerialElemNames.add("3"); + CPUSerialElemNames.add("4"); + CPUSerialElemNames.add("5"); + CPUSerialElemNames.add("6"); + CPUSerialElemNames.add("7"); + CPUSerialElemNames.add("8"); + CPUSerialElemNames.add("9"); + CPUSerialElemNames.add("10"); + CPUSerialElemNames.add("11"); + fields.add( new UAVObjectField("CPUSerial", "", UAVObjectField.FieldType.UINT8, CPUSerialElemNames, null) ); + + List BoardTypeElemNames = new ArrayList(); + BoardTypeElemNames.add("0"); + fields.add( new UAVObjectField("BoardType", "", UAVObjectField.FieldType.UINT8, BoardTypeElemNames, null) ); + + List FrequencyBandElemNames = new ArrayList(); + FrequencyBandElemNames.add("0"); + fields.add( new UAVObjectField("FrequencyBand", "", UAVObjectField.FieldType.UINT8, FrequencyBandElemNames, null) ); + + List RSSIElemNames = new ArrayList(); + RSSIElemNames.add("0"); + fields.add( new UAVObjectField("RSSI", "dBm", UAVObjectField.FieldType.INT8, RSSIElemNames, null) ); + + List LinkStateElemNames = new ArrayList(); + LinkStateElemNames.add("0"); + List LinkStateEnumOptions = new ArrayList(); + LinkStateEnumOptions.add("Disconnected"); + LinkStateEnumOptions.add("Connecting"); + LinkStateEnumOptions.add("Connected"); + fields.add( new UAVObjectField("LinkState", "function", UAVObjectField.FieldType.ENUM, LinkStateElemNames, LinkStateEnumOptions) ); + + List PairSignalStrengthsElemNames = new ArrayList(); + PairSignalStrengthsElemNames.add("0"); + PairSignalStrengthsElemNames.add("1"); + PairSignalStrengthsElemNames.add("2"); + PairSignalStrengthsElemNames.add("3"); + fields.add( new UAVObjectField("PairSignalStrengths", "dBm", UAVObjectField.FieldType.INT8, PairSignalStrengthsElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("MinFrequency").setValue(0); + getField("MaxFrequency").setValue(0); + getField("FrequencyStepSize").setValue(0); + getField("DeviceID").setValue(0); + getField("AFC").setValue(0); + getField("PairIDs").setValue(0,0); + getField("PairIDs").setValue(0,1); + getField("PairIDs").setValue(0,2); + getField("PairIDs").setValue(0,3); + getField("Retries").setValue(0); + getField("Errors").setValue(0); + getField("UAVTalkErrors").setValue(0); + getField("Dropped").setValue(0); + getField("Resets").setValue(0); + getField("TXRate").setValue(0); + getField("RXRate").setValue(0); + getField("FrequencyBand").setValue(0); + getField("RSSI").setValue(0); + getField("LinkState").setValue("Disconnected"); + getField("PairSignalStrengths").setValue(-127,0); + getField("PairSignalStrengths").setValue(-127,1); + getField("PairSignalStrengths").setValue(-127,2); + getField("PairSignalStrengths").setValue(-127,3); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + PipXStatus obj = new PipXStatus(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public PipXStatus GetInstance(UAVObjectManager objMngr, int instID) + { + return (PipXStatus)(objMngr.getObject(PipXStatus.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x3FC68A86; + protected static final String NAME = "PipXStatus"; + protected static String DESCRIPTION = "PipXtreme device status."; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java new file mode 100644 index 000000000..940f78875 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java @@ -0,0 +1,249 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the INS to control the algorithm and what is updated + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the INS to control the algorithm and what is updated + +generated from revocalibration.xml + **/ +public class RevoCalibration extends UAVDataObject { + + public RevoCalibration() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List accel_biasElemNames = new ArrayList(); + accel_biasElemNames.add("X"); + accel_biasElemNames.add("Y"); + accel_biasElemNames.add("Z"); + fields.add( new UAVObjectField("accel_bias", "m/s", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); + + List accel_scaleElemNames = new ArrayList(); + accel_scaleElemNames.add("X"); + accel_scaleElemNames.add("Y"); + accel_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("accel_scale", "gain", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); + + List accel_varElemNames = new ArrayList(); + accel_varElemNames.add("X"); + accel_varElemNames.add("Y"); + accel_varElemNames.add("Z"); + fields.add( new UAVObjectField("accel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); + + List gyro_biasElemNames = new ArrayList(); + gyro_biasElemNames.add("X"); + gyro_biasElemNames.add("Y"); + gyro_biasElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_bias", "deg/s", UAVObjectField.FieldType.FLOAT32, gyro_biasElemNames, null) ); + + List gyro_scaleElemNames = new ArrayList(); + gyro_scaleElemNames.add("X"); + gyro_scaleElemNames.add("Y"); + gyro_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_scale", "gain", UAVObjectField.FieldType.FLOAT32, gyro_scaleElemNames, null) ); + + List gyro_varElemNames = new ArrayList(); + gyro_varElemNames.add("X"); + gyro_varElemNames.add("Y"); + gyro_varElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_var", "(deg/s)^2", UAVObjectField.FieldType.FLOAT32, gyro_varElemNames, null) ); + + List gyro_tempcoeffElemNames = new ArrayList(); + gyro_tempcoeffElemNames.add("X"); + gyro_tempcoeffElemNames.add("Y"); + gyro_tempcoeffElemNames.add("Z"); + fields.add( new UAVObjectField("gyro_tempcoeff", "(deg/s)/deg", UAVObjectField.FieldType.FLOAT32, gyro_tempcoeffElemNames, null) ); + + List mag_biasElemNames = new ArrayList(); + mag_biasElemNames.add("X"); + mag_biasElemNames.add("Y"); + mag_biasElemNames.add("Z"); + fields.add( new UAVObjectField("mag_bias", "mGau", UAVObjectField.FieldType.FLOAT32, mag_biasElemNames, null) ); + + List mag_scaleElemNames = new ArrayList(); + mag_scaleElemNames.add("X"); + mag_scaleElemNames.add("Y"); + mag_scaleElemNames.add("Z"); + fields.add( new UAVObjectField("mag_scale", "gain", UAVObjectField.FieldType.FLOAT32, mag_scaleElemNames, null) ); + + List mag_varElemNames = new ArrayList(); + mag_varElemNames.add("X"); + mag_varElemNames.add("Y"); + mag_varElemNames.add("Z"); + fields.add( new UAVObjectField("mag_var", "mGau^2", UAVObjectField.FieldType.FLOAT32, mag_varElemNames, null) ); + + List gps_varElemNames = new ArrayList(); + gps_varElemNames.add("Pos"); + gps_varElemNames.add("Vel"); + fields.add( new UAVObjectField("gps_var", "m^2", UAVObjectField.FieldType.FLOAT32, gps_varElemNames, null) ); + + List baro_varElemNames = new ArrayList(); + baro_varElemNames.add("0"); + fields.add( new UAVObjectField("baro_var", "m^2", UAVObjectField.FieldType.FLOAT32, baro_varElemNames, null) ); + + List MagBiasNullingRateElemNames = new ArrayList(); + MagBiasNullingRateElemNames.add("0"); + fields.add( new UAVObjectField("MagBiasNullingRate", "", UAVObjectField.FieldType.FLOAT32, MagBiasNullingRateElemNames, null) ); + + List BiasCorrectedRawElemNames = new ArrayList(); + BiasCorrectedRawElemNames.add("0"); + List BiasCorrectedRawEnumOptions = new ArrayList(); + BiasCorrectedRawEnumOptions.add("FALSE"); + BiasCorrectedRawEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("accel_bias").setValue(0,0); + getField("accel_bias").setValue(0,1); + getField("accel_bias").setValue(0,2); + getField("accel_scale").setValue(1,0); + getField("accel_scale").setValue(1,1); + getField("accel_scale").setValue(1,2); + getField("accel_var").setValue(0.01,0); + getField("accel_var").setValue(0.01,1); + getField("accel_var").setValue(0.01,2); + getField("gyro_bias").setValue(0,0); + getField("gyro_bias").setValue(0,1); + getField("gyro_bias").setValue(0,2); + getField("gyro_scale").setValue(1,0); + getField("gyro_scale").setValue(1,1); + getField("gyro_scale").setValue(1,2); + getField("gyro_var").setValue(0.01,0); + getField("gyro_var").setValue(0.01,1); + getField("gyro_var").setValue(0.01,2); + getField("gyro_tempcoeff").setValue(1,0); + getField("gyro_tempcoeff").setValue(1,1); + getField("gyro_tempcoeff").setValue(1,2); + getField("mag_bias").setValue(0,0); + getField("mag_bias").setValue(0,1); + getField("mag_bias").setValue(0,2); + getField("mag_scale").setValue(1,0); + getField("mag_scale").setValue(1,1); + getField("mag_scale").setValue(1,2); + getField("mag_var").setValue(0.01,0); + getField("mag_var").setValue(0.01,1); + getField("mag_var").setValue(10,2); + getField("gps_var").setValue(1,0); + getField("gps_var").setValue(1,1); + getField("baro_var").setValue(1); + getField("MagBiasNullingRate").setValue(0); + getField("BiasCorrectedRaw").setValue("TRUE"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + RevoCalibration obj = new RevoCalibration(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public RevoCalibration GetInstance(UAVObjectManager objMngr, int instID) + { + return (RevoCalibration)(objMngr.getObject(RevoCalibration.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xA2A63C7C; + protected static final String NAME = "RevoCalibration"; + protected static String DESCRIPTION = "Settings for the INS to control the algorithm and what is updated"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java new file mode 100644 index 000000000..5e36565b2 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java @@ -0,0 +1,143 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the revo to control the algorithm and what is updated + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the revo to control the algorithm and what is updated + +generated from revosettings.xml + **/ +public class RevoSettings extends UAVDataObject { + + public RevoSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List FusionAlgorithmElemNames = new ArrayList(); + FusionAlgorithmElemNames.add("0"); + List FusionAlgorithmEnumOptions = new ArrayList(); + FusionAlgorithmEnumOptions.add("Complimentary"); + FusionAlgorithmEnumOptions.add("INSIndoor"); + FusionAlgorithmEnumOptions.add("INSOutdoor"); + fields.add( new UAVObjectField("FusionAlgorithm", "", UAVObjectField.FieldType.ENUM, FusionAlgorithmElemNames, FusionAlgorithmEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("FusionAlgorithm").setValue("Complimentary"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + RevoSettings obj = new RevoSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public RevoSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (RevoSettings)(objMngr.getObject(RevoSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0xE2DA70EA; + protected static final String NAME = "RevoSettings"; + protected static String DESCRIPTION = "Settings for the revo to control the algorithm and what is updated"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java new file mode 100644 index 000000000..789f31b3f --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java @@ -0,0 +1,225 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter + +generated from txpidsettings.xml + **/ +public class TxPIDSettings extends UAVDataObject { + + public TxPIDSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List ThrottleRangeElemNames = new ArrayList(); + ThrottleRangeElemNames.add("Min"); + ThrottleRangeElemNames.add("Max"); + fields.add( new UAVObjectField("ThrottleRange", "%", UAVObjectField.FieldType.FLOAT32, ThrottleRangeElemNames, null) ); + + List MinPIDElemNames = new ArrayList(); + MinPIDElemNames.add("Instance1"); + MinPIDElemNames.add("Instance2"); + MinPIDElemNames.add("Instance3"); + fields.add( new UAVObjectField("MinPID", "", UAVObjectField.FieldType.FLOAT32, MinPIDElemNames, null) ); + + List MaxPIDElemNames = new ArrayList(); + MaxPIDElemNames.add("Instance1"); + MaxPIDElemNames.add("Instance2"); + MaxPIDElemNames.add("Instance3"); + fields.add( new UAVObjectField("MaxPID", "", UAVObjectField.FieldType.FLOAT32, MaxPIDElemNames, null) ); + + List UpdateModeElemNames = new ArrayList(); + UpdateModeElemNames.add("0"); + List UpdateModeEnumOptions = new ArrayList(); + UpdateModeEnumOptions.add("Never"); + UpdateModeEnumOptions.add("When Armed"); + UpdateModeEnumOptions.add("Always"); + fields.add( new UAVObjectField("UpdateMode", "option", UAVObjectField.FieldType.ENUM, UpdateModeElemNames, UpdateModeEnumOptions) ); + + List InputsElemNames = new ArrayList(); + InputsElemNames.add("Instance1"); + InputsElemNames.add("Instance2"); + InputsElemNames.add("Instance3"); + List InputsEnumOptions = new ArrayList(); + InputsEnumOptions.add("Throttle"); + InputsEnumOptions.add("Accessory0"); + InputsEnumOptions.add("Accessory1"); + InputsEnumOptions.add("Accessory2"); + InputsEnumOptions.add("Accessory3"); + InputsEnumOptions.add("Accessory4"); + InputsEnumOptions.add("Accessory5"); + fields.add( new UAVObjectField("Inputs", "channel", UAVObjectField.FieldType.ENUM, InputsElemNames, InputsEnumOptions) ); + + List PIDsElemNames = new ArrayList(); + PIDsElemNames.add("Instance1"); + PIDsElemNames.add("Instance2"); + PIDsElemNames.add("Instance3"); + List PIDsEnumOptions = new ArrayList(); + PIDsEnumOptions.add("Disabled"); + PIDsEnumOptions.add("Roll Rate.Kp"); + PIDsEnumOptions.add("Pitch Rate.Kp"); + PIDsEnumOptions.add("Roll+Pitch Rate.Kp"); + PIDsEnumOptions.add("Yaw Rate.Kp"); + PIDsEnumOptions.add("Roll Rate.Ki"); + PIDsEnumOptions.add("Pitch Rate.Ki"); + PIDsEnumOptions.add("Roll+Pitch Rate.Ki"); + PIDsEnumOptions.add("Yaw Rate.Ki"); + PIDsEnumOptions.add("Roll Rate.Kd"); + PIDsEnumOptions.add("Pitch Rate.Kd"); + PIDsEnumOptions.add("Roll+Pitch Rate.Kd"); + PIDsEnumOptions.add("Yaw Rate.Kd"); + PIDsEnumOptions.add("Roll Rate.ILimit"); + PIDsEnumOptions.add("Pitch Rate.ILimit"); + PIDsEnumOptions.add("Roll+Pitch Rate.ILimit"); + PIDsEnumOptions.add("Yaw Rate.ILimit"); + PIDsEnumOptions.add("Roll Attitude.Kp"); + PIDsEnumOptions.add("Pitch Attitude.Kp"); + PIDsEnumOptions.add("Roll+Pitch Attitude.Kp"); + PIDsEnumOptions.add("Yaw Attitude.Kp"); + PIDsEnumOptions.add("Roll Attitude.Ki"); + PIDsEnumOptions.add("Pitch Attitude.Ki"); + PIDsEnumOptions.add("Roll+Pitch Attitude.Ki"); + PIDsEnumOptions.add("Yaw Attitude.Ki"); + PIDsEnumOptions.add("Roll Attitude.ILimit"); + PIDsEnumOptions.add("Pitch Attitude.ILimit"); + PIDsEnumOptions.add("Roll+Pitch Attitude.ILimit"); + PIDsEnumOptions.add("Yaw Attitude.ILimit"); + PIDsEnumOptions.add("GyroTau"); + fields.add( new UAVObjectField("PIDs", "option", UAVObjectField.FieldType.ENUM, PIDsElemNames, PIDsEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("ThrottleRange").setValue(0.2,0); + getField("ThrottleRange").setValue(0.8,1); + getField("MinPID").setValue(0,0); + getField("MinPID").setValue(0,1); + getField("MinPID").setValue(0,2); + getField("MaxPID").setValue(0,0); + getField("MaxPID").setValue(0,1); + getField("MaxPID").setValue(0,2); + getField("UpdateMode").setValue("When Armed"); + getField("Inputs").setValue("Throttle",0); + getField("Inputs").setValue("Accessory0",1); + getField("Inputs").setValue("Accessory1",2); + getField("PIDs").setValue("Disabled",0); + getField("PIDs").setValue("Disabled",1); + getField("PIDs").setValue("Disabled",2); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + TxPIDSettings obj = new TxPIDSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public TxPIDSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (TxPIDSettings)(objMngr.getObject(TxPIDSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x42B2D2AE; + protected static final String NAME = "TxPIDSettings"; + protected static String DESCRIPTION = "Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java new file mode 100644 index 000000000..b3c01dc8a --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java @@ -0,0 +1,232 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Settings for the @ref VtolPathFollower module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Settings for the @ref VtolPathFollower module + +generated from vtolpathfollowersettings.xml + **/ +public class VtolPathFollowerSettings extends UAVDataObject { + + public VtolPathFollowerSettings() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List HorizontalPosPIElemNames = new ArrayList(); + HorizontalPosPIElemNames.add("Kp"); + HorizontalPosPIElemNames.add("Ki"); + HorizontalPosPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("HorizontalPosPI", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); + + List HorizontalVelPIDElemNames = new ArrayList(); + HorizontalVelPIDElemNames.add("Kp"); + HorizontalVelPIDElemNames.add("Ki"); + HorizontalVelPIDElemNames.add("Kd"); + HorizontalVelPIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("HorizontalVelPID", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); + + List VerticalPosPIElemNames = new ArrayList(); + VerticalPosPIElemNames.add("Kp"); + VerticalPosPIElemNames.add("Ki"); + VerticalPosPIElemNames.add("ILimit"); + fields.add( new UAVObjectField("VerticalPosPI", "", UAVObjectField.FieldType.FLOAT32, VerticalPosPIElemNames, null) ); + + List VerticalVelPIDElemNames = new ArrayList(); + VerticalVelPIDElemNames.add("Kp"); + VerticalVelPIDElemNames.add("Ki"); + VerticalVelPIDElemNames.add("Kd"); + VerticalVelPIDElemNames.add("ILimit"); + fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); + + List VelocityFeedforwardElemNames = new ArrayList(); + VelocityFeedforwardElemNames.add("0"); + fields.add( new UAVObjectField("VelocityFeedforward", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, VelocityFeedforwardElemNames, null) ); + + List MaxRollPitchElemNames = new ArrayList(); + MaxRollPitchElemNames.add("0"); + fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); + + List UpdatePeriodElemNames = new ArrayList(); + UpdatePeriodElemNames.add("0"); + fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); + + List HorizontalVelMaxElemNames = new ArrayList(); + HorizontalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("HorizontalVelMax", "m/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); + + List VerticalVelMaxElemNames = new ArrayList(); + VerticalVelMaxElemNames.add("0"); + fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); + + List GuidanceModeElemNames = new ArrayList(); + GuidanceModeElemNames.add("0"); + List GuidanceModeEnumOptions = new ArrayList(); + GuidanceModeEnumOptions.add("DUAL_LOOP"); + GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); + fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); + + List ThrottleControlElemNames = new ArrayList(); + ThrottleControlElemNames.add("0"); + List ThrottleControlEnumOptions = new ArrayList(); + ThrottleControlEnumOptions.add("FALSE"); + ThrottleControlEnumOptions.add("TRUE"); + fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); + + List VelocitySourceElemNames = new ArrayList(); + VelocitySourceElemNames.add("0"); + List VelocitySourceEnumOptions = new ArrayList(); + VelocitySourceEnumOptions.add("EKF"); + VelocitySourceEnumOptions.add("NEDVEL"); + VelocitySourceEnumOptions.add("GPSPOS"); + fields.add( new UAVObjectField("VelocitySource", "", UAVObjectField.FieldType.ENUM, VelocitySourceElemNames, VelocitySourceEnumOptions) ); + + List PositionSourceElemNames = new ArrayList(); + PositionSourceElemNames.add("0"); + List PositionSourceEnumOptions = new ArrayList(); + PositionSourceEnumOptions.add("EKF"); + PositionSourceEnumOptions.add("GPSPOS"); + fields.add( new UAVObjectField("PositionSource", "", UAVObjectField.FieldType.ENUM, PositionSourceElemNames, PositionSourceEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 0; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + getField("HorizontalPosPI").setValue(1,0); + getField("HorizontalPosPI").setValue(0,1); + getField("HorizontalPosPI").setValue(0,2); + getField("HorizontalVelPID").setValue(5,0); + getField("HorizontalVelPID").setValue(0,1); + getField("HorizontalVelPID").setValue(1,2); + getField("HorizontalVelPID").setValue(0,3); + getField("VerticalPosPI").setValue(0.1,0); + getField("VerticalPosPI").setValue(0.001,1); + getField("VerticalPosPI").setValue(200,2); + getField("VerticalVelPID").setValue(0.1,0); + getField("VerticalVelPID").setValue(0,1); + getField("VerticalVelPID").setValue(0,2); + getField("VerticalVelPID").setValue(0,3); + getField("VelocityFeedforward").setValue(0); + getField("MaxRollPitch").setValue(20); + getField("UpdatePeriod").setValue(100); + getField("HorizontalVelMax").setValue(10); + getField("VerticalVelMax").setValue(1); + getField("GuidanceMode").setValue("DUAL_LOOP"); + getField("ThrottleControl").setValue("FALSE"); + getField("VelocitySource").setValue("EKF"); + getField("PositionSource").setValue("EKF"); + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + VtolPathFollowerSettings obj = new VtolPathFollowerSettings(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public VtolPathFollowerSettings GetInstance(UAVObjectManager objMngr, int instID) + { + return (VtolPathFollowerSettings)(objMngr.getObject(VtolPathFollowerSettings.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x973991F6; + protected static final String NAME = "VtolPathFollowerSettings"; + protected static String DESCRIPTION = "Settings for the @ref VtolPathFollower module"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 1 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java new file mode 100644 index 000000000..4db7179ad --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module + +generated from waypoint.xml + **/ +public class Waypoint extends UAVDataObject { + + public Waypoint() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List PositionElemNames = new ArrayList(); + PositionElemNames.add("North"); + PositionElemNames.add("East"); + PositionElemNames.add("Down"); + fields.add( new UAVObjectField("Position", "m", UAVObjectField.FieldType.FLOAT32, PositionElemNames, null) ); + + List VelocityElemNames = new ArrayList(); + VelocityElemNames.add("North"); + VelocityElemNames.add("East"); + VelocityElemNames.add("Down"); + fields.add( new UAVObjectField("Velocity", "m/s", UAVObjectField.FieldType.FLOAT32, VelocityElemNames, null) ); + + List YawDesiredElemNames = new ArrayList(); + YawDesiredElemNames.add("0"); + fields.add( new UAVObjectField("YawDesired", "deg", UAVObjectField.FieldType.FLOAT32, YawDesiredElemNames, null) ); + + List ActionElemNames = new ArrayList(); + ActionElemNames.add("0"); + List ActionEnumOptions = new ArrayList(); + ActionEnumOptions.add("PathToNext"); + ActionEnumOptions.add("EndpointToNext"); + ActionEnumOptions.add("Land"); + ActionEnumOptions.add("Stop"); + fields.add( new UAVObjectField("Action", "", UAVObjectField.FieldType.ENUM, ActionElemNames, ActionEnumOptions) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 4000; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + Waypoint obj = new Waypoint(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public Waypoint GetInstance(UAVObjectManager objMngr, int instID) + { + return (Waypoint)(objMngr.getObject(Waypoint.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x338C5F90; + protected static final String NAME = "Waypoint"; + protected static String DESCRIPTION = "A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module"; + protected static final boolean ISSINGLEINST = 0 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java new file mode 100644 index 000000000..06f3ab6c4 --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java @@ -0,0 +1,138 @@ +/** + ****************************************************************************** + * + * @file uavobjecttemplate.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Template for an uavobject in java + * This is a autogenerated file!! Do not modify and expect a result. + * Indicates the currently active waypoint + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +package org.openpilot.uavtalk.uavobjects; + +import java.nio.ByteBuffer; +import java.util.ArrayList; +import java.util.List; +import java.util.ListIterator; + +import org.openpilot.uavtalk.UAVObjectManager; +import org.openpilot.uavtalk.UAVObject; +import org.openpilot.uavtalk.UAVDataObject; +import org.openpilot.uavtalk.UAVObjectField; + +/** +Indicates the currently active waypoint + +generated from waypointactive.xml + **/ +public class WaypointActive extends UAVDataObject { + + public WaypointActive() { + super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); + + List fields = new ArrayList(); + + + List IndexElemNames = new ArrayList(); + IndexElemNames.add("0"); + fields.add( new UAVObjectField("Index", "", UAVObjectField.FieldType.UINT8, IndexElemNames, null) ); + + + // Compute the number of bytes for this object + int numBytes = 0; + ListIterator li = fields.listIterator(); + while(li.hasNext()) { + numBytes += li.next().getNumBytes(); + } + NUMBYTES = numBytes; + + // Initialize object + initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); + // Set the default field values + setDefaultFieldValues(); + // Set the object description + setDescription(DESCRIPTION); + } + + /** + * Create a Metadata object filled with default values for this object + * @return Metadata object with default values + */ + public Metadata getDefaultMetadata() { + UAVObject.Metadata metadata = new UAVObject.Metadata(); + metadata.flags = + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | + UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | + 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | + 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.flightTelemetryUpdatePeriod = 0; + metadata.gcsTelemetryUpdatePeriod = 0; + metadata.loggingUpdatePeriod = 1000; + + return metadata; + } + + /** + * Initialize object fields with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ + public void setDefaultFieldValues() + { + + } + + /** + * Create a clone of this object, a new instance ID must be specified. + * Do not use this function directly to create new instances, the + * UAVObjectManager should be used instead. + */ + public UAVDataObject clone(int instID) { + // TODO: Need to get specific instance to clone + try { + WaypointActive obj = new WaypointActive(); + obj.initialize(instID, this.getMetaObject()); + return obj; + } catch (Exception e) { + return null; + } + } + + /** + * Static function to retrieve an instance of the object. + */ + public WaypointActive GetInstance(UAVObjectManager objMngr, int instID) + { + return (WaypointActive)(objMngr.getObject(WaypointActive.OBJID, instID)); + } + + // Constants + protected static final int OBJID = 0x1EA5B192; + protected static final String NAME = "WaypointActive"; + protected static String DESCRIPTION = "Indicates the currently active waypoint"; + protected static final boolean ISSINGLEINST = 1 == 1; + protected static final boolean ISSETTINGS = 0 == 1; + protected static int NUMBYTES = 0; + + +} \ No newline at end of file From 45f4ae0701b28581798c4020ee66bb542643bca2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 02:14:12 -0500 Subject: [PATCH 256/543] Allow selecting the IP address from the preferences --- androidgcs/res/xml/preferences.xml | 2 +- .../src/org/openpilot/androidgcs/TcpUAVTalk.java | 13 +++++++++---- 2 files changed, 10 insertions(+), 5 deletions(-) diff --git a/androidgcs/res/xml/preferences.xml b/androidgcs/res/xml/preferences.xml index 24fd43b5e..285e7b6d7 100644 --- a/androidgcs/res/xml/preferences.xml +++ b/androidgcs/res/xml/preferences.xml @@ -10,6 +10,6 @@ + android:key="ip_address" /> diff --git a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java index 47074f968..f5d40040b 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java @@ -8,6 +8,8 @@ import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; import android.content.Context; +import android.content.SharedPreferences; +import android.preference.PreferenceManager; import android.util.Log; public class TcpUAVTalk { @@ -17,14 +19,17 @@ public class TcpUAVTalk { public static boolean DEBUG = LOGLEVEL > 0; // Temporarily define fixed device name - public final static String IP_ADDRESS = "10.21.18.120"; + private String ip_address = "1"; public final static int PORT = 9001; private UAVTalk uavTalk; private boolean connected; public TcpUAVTalk(Context caller) { - if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + IP_ADDRESS); + SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(caller); + ip_address = prefs.getString("ip_address","127.0.0.1"); + + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + ip_address); connected = false; } @@ -47,11 +52,11 @@ public class TcpUAVTalk { private boolean openTelemetryTcp(UAVObjectManager objMngr) { - Log.d(TAG, "Opening conncetion to " + IP_ADDRESS + " at address " + PORT); + Log.d(TAG, "Opening connection to " + ip_address + " at address " + PORT); InetAddress serverAddr = null; try { - serverAddr = InetAddress.getByName(IP_ADDRESS); + serverAddr = InetAddress.getByName(ip_address); } catch (UnknownHostException e1) { // TODO Auto-generated catch block e1.printStackTrace(); From 20b585383d4db87bae20b123676e7cd2a3e27791 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 03:18:26 -0500 Subject: [PATCH 257/543] Make port and bluetooth adapter be listed in the preferences. Using the BT adapter not working yet. --- androidgcs/res/xml/preferences.xml | 8 ++++++++ .../openpilot/androidgcs/BluetoothUAVTalk.java | 17 ++++++++++++----- .../androidgcs/OPTelemetryService.java | 2 +- .../org/openpilot/androidgcs/TcpUAVTalk.java | 12 ++++++++---- 4 files changed, 29 insertions(+), 10 deletions(-) diff --git a/androidgcs/res/xml/preferences.xml b/androidgcs/res/xml/preferences.xml index 285e7b6d7..3a9103b49 100644 --- a/androidgcs/res/xml/preferences.xml +++ b/androidgcs/res/xml/preferences.xml @@ -11,5 +11,13 @@ android:summary="Enter a TCP/IP address here" android:defaultValue="192.168.0.1" android:title="IP address:" android:key="ip_address" /> + + diff --git a/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java index b240f3adc..c00db0bea 100644 --- a/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/BluetoothUAVTalk.java @@ -7,6 +7,7 @@ import java.util.UUID; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; +import android.annotation.TargetApi; import android.app.Activity; import android.bluetooth.BluetoothAdapter; import android.bluetooth.BluetoothDevice; @@ -14,16 +15,18 @@ import android.bluetooth.BluetoothSocket; import android.content.BroadcastReceiver; import android.content.Context; import android.content.Intent; +import android.content.SharedPreferences; +import android.preference.PreferenceManager; import android.util.Log; -public class BluetoothUAVTalk { +@TargetApi(10) public class BluetoothUAVTalk { private final String TAG = "BluetoothUAVTalk"; public static int LOGLEVEL = 2; public static boolean WARN = LOGLEVEL > 1; public static boolean DEBUG = LOGLEVEL > 0; // Temporarily define fixed device name - public final static String DEVICE_NAME = "RN42-222D"; + private String device_name = "RN42-222D"; private final static UUID MY_UUID = UUID.fromString("00001101-0000-1000-8000-00805F9B34FB"); private BluetoothAdapter mBluetoothAdapter; @@ -32,8 +35,12 @@ public class BluetoothUAVTalk { private UAVTalk uavTalk; private boolean connected; - public BluetoothUAVTalk(Context caller, String deviceName) { - if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + deviceName); + public BluetoothUAVTalk(Context caller) { + + SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(caller); + device_name = prefs.getString("bluetooth_mac",""); + + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + device_name); connected = false; device = null; @@ -93,7 +100,7 @@ public class BluetoothUAVTalk { // Add the name and address to an array adapter to show in a ListView //mArrayAdapter.add(device.getName() + "\n" + device.getAddress()); Log.d(TAG, "Paired device: " + device.getName()); - if(device.getName().compareTo(DEVICE_NAME) == 0) { + if(device.getName().compareTo(device_name) == 0) { this.device = device; return; } diff --git a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java index 917dfb116..13e415c54 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/OPTelemetryService.java @@ -277,7 +277,7 @@ public class OPTelemetryService extends Service { Looper.prepare(); - BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this, BluetoothUAVTalk.DEVICE_NAME); + BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this); for( int i = 0; i < 10; i++ ) { if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); diff --git a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java index f5d40040b..1f647bd99 100644 --- a/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java +++ b/androidgcs/src/org/openpilot/androidgcs/TcpUAVTalk.java @@ -20,7 +20,7 @@ public class TcpUAVTalk { // Temporarily define fixed device name private String ip_address = "1"; - public final static int PORT = 9001; + private int port = 9001; private UAVTalk uavTalk; private boolean connected; @@ -28,8 +28,12 @@ public class TcpUAVTalk { public TcpUAVTalk(Context caller) { SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(caller); ip_address = prefs.getString("ip_address","127.0.0.1"); + try { + port = Integer.decode(prefs.getString("port", "")); + } catch (NumberFormatException e) { + } - if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + ip_address); + if (DEBUG) Log.d(TAG, "Trying to open UAVTalk with " + ip_address); connected = false; } @@ -52,7 +56,7 @@ public class TcpUAVTalk { private boolean openTelemetryTcp(UAVObjectManager objMngr) { - Log.d(TAG, "Opening connection to " + ip_address + " at address " + PORT); + Log.d(TAG, "Opening connection to " + ip_address + " at address " + port); InetAddress serverAddr = null; try { @@ -65,7 +69,7 @@ public class TcpUAVTalk { Socket socket = null; try { - socket = new Socket(serverAddr,PORT); + socket = new Socket(serverAddr,port); } catch (IOException e1) { // TODO Auto-generated catch block e1.printStackTrace(); From a44e84ff9bfad12d35592c155e0e24eb64f5dceb Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 21:00:25 -0500 Subject: [PATCH 258/543] Update the sdk version --- androidgcs/AndroidManifest.xml | 2 +- androidgcs/project.properties | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index c18dc0cb1..40b08c328 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -2,7 +2,7 @@ - + diff --git a/androidgcs/project.properties b/androidgcs/project.properties index 5d85d779c..a43ea8cdc 100644 --- a/androidgcs/project.properties +++ b/androidgcs/project.properties @@ -8,4 +8,4 @@ # project structure. # Project target. -target=Google Inc.:Google APIs:13 +target=Google Inc.:Google APIs:16 From bf9343532241536197d93031cff7d38af18d93bd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 21:00:54 -0500 Subject: [PATCH 259/543] Check in a joystick gadget class --- .../Android/Widgets/DockPanel/DockPanel.java | 319 +++++++++++ .../Widgets/DockPanel/DockPosition.java | 5 + .../DragAndDrop/DragAndDropManager.java | 124 +++++ .../Widgets/DragAndDrop/DragSurface.java | 94 ++++ .../Widgets/DragAndDrop/DraggableItem.java | 44 ++ .../DragAndDrop/DraggableViewsFactory.java | 19 + .../Android/Widgets/DragAndDrop/DropZone.java | 67 +++ .../DragAndDrop/DropZoneEventsListener.java | 9 + .../Widgets/Joystick/DualJoystickView.java | 147 +++++ .../Joystick/JoystickClickedListener.java | 6 + .../Joystick/JoystickMovedListener.java | 7 + .../Widgets/Joystick/JoystickView.java | 521 ++++++++++++++++++ .../ThresholdEditText/ThresholdEditText.java | 169 ++++++ .../ThresholdTextChanged.java | 7 + .../Widgets/TilesLayout/SingleTileLayout.java | 68 +++ .../Widgets/TilesLayout/TilePosition.java | 63 +++ .../Widgets/TilesLayout/TilesLayout.java | 299 ++++++++++ .../TilesLayout/TilesLayoutPreset.java | 157 ++++++ 18 files changed, 2125 insertions(+) create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPanel.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPosition.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragAndDropManager.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragSurface.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableItem.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableViewsFactory.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZone.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZoneEventsListener.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/DualJoystickView.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickClickedListener.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickMovedListener.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickView.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdEditText.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdTextChanged.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/SingleTileLayout.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilePosition.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayout.java create mode 100644 androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayoutPreset.java diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPanel.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPanel.java new file mode 100644 index 000000000..e2397394e --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPanel.java @@ -0,0 +1,319 @@ +package com.MobileAnarchy.Android.Widgets.DockPanel; + +import android.content.Context; +import android.graphics.Color; +import android.util.AttributeSet; +import android.util.Log; +import android.view.Gravity; +import android.view.LayoutInflater; +import android.view.View; +import android.view.animation.AccelerateInterpolator; +import android.view.animation.Animation; +import android.view.animation.DecelerateInterpolator; +import android.view.animation.TranslateAnimation; +import android.view.animation.Animation.AnimationListener; +import android.widget.FrameLayout; +import android.widget.ImageButton; +import android.widget.LinearLayout; + +public class DockPanel extends LinearLayout { + + // ========================================= + // Private members + // ========================================= + + private static final String TAG = "DockPanel"; + private DockPosition position; + private int contentLayoutId; + private int handleButtonDrawableId; + private Boolean isOpen; + private Boolean animationRunning; + private FrameLayout contentPlaceHolder; + private ImageButton toggleButton; + private int animationDuration; + + // ========================================= + // Constructors + // ========================================= + + public DockPanel(Context context, int contentLayoutId, + int handleButtonDrawableId, Boolean isOpen) { + super(context); + + this.contentLayoutId = contentLayoutId; + this.handleButtonDrawableId = handleButtonDrawableId; + this.isOpen = isOpen; + + Init(null); + } + + public DockPanel(Context context, AttributeSet attrs) { + super(context, attrs); + + // to prevent from crashing the designer + try { + Init(attrs); + } catch (Exception ex) { + } + } + + // ========================================= + // Initialization + // ========================================= + + private void Init(AttributeSet attrs) { + setDefaultValues(attrs); + + createHandleToggleButton(); + + // create the handle container + FrameLayout handleContainer = new FrameLayout(getContext()); + handleContainer.addView(toggleButton); + + // create and populate the panel's container, and inflate it + contentPlaceHolder = new FrameLayout(getContext()); + String infService = Context.LAYOUT_INFLATER_SERVICE; + LayoutInflater li = (LayoutInflater) getContext().getSystemService( + infService); + li.inflate(contentLayoutId, contentPlaceHolder, true); + + // setting the layout of the panel parameters according to the docking + // position + if (position == DockPosition.LEFT || position == DockPosition.RIGHT) { + handleContainer.setLayoutParams(new LayoutParams( + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, + android.view.ViewGroup.LayoutParams.FILL_PARENT, 1)); + contentPlaceHolder.setLayoutParams(new LayoutParams( + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, + android.view.ViewGroup.LayoutParams.FILL_PARENT, 1)); + } else { + handleContainer.setLayoutParams(new LayoutParams( + android.view.ViewGroup.LayoutParams.FILL_PARENT, + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, 1)); + contentPlaceHolder.setLayoutParams(new LayoutParams( + android.view.ViewGroup.LayoutParams.FILL_PARENT, + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, 1)); + } + + // adding the view to the parent layout according to docking position + if (position == DockPosition.RIGHT || position == DockPosition.BOTTOM) { + this.addView(handleContainer); + this.addView(contentPlaceHolder); + } else { + this.addView(contentPlaceHolder); + this.addView(handleContainer); + } + + if (!isOpen) { + contentPlaceHolder.setVisibility(GONE); + } + } + + private void setDefaultValues(AttributeSet attrs) { + // set default values + isOpen = true; + animationRunning = false; + animationDuration = 500; + setPosition(DockPosition.RIGHT); + + // Try to load values set by xml markup + if (attrs != null) { + String namespace = "http://com.MobileAnarchy.Android.Widgets"; + + animationDuration = attrs.getAttributeIntValue(namespace, + "animationDuration", 500); + contentLayoutId = attrs.getAttributeResourceValue(namespace, + "contentLayoutId", 0); + handleButtonDrawableId = attrs.getAttributeResourceValue( + namespace, "handleButtonDrawableResourceId", 0); + isOpen = attrs.getAttributeBooleanValue(namespace, "isOpen", true); + + // Enums are a bit trickier (needs to be parsed) + try { + position = DockPosition.valueOf(attrs.getAttributeValue( + namespace, "dockPosition").toUpperCase()); + setPosition(position); + } catch (Exception ex) { + // Docking to the left is the default behavior + setPosition(DockPosition.LEFT); + } + } + } + + private void createHandleToggleButton() { + toggleButton = new ImageButton(getContext()); + toggleButton.setPadding(0, 0, 0, 0); + toggleButton.setLayoutParams(new FrameLayout.LayoutParams( + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, + android.view.ViewGroup.LayoutParams.WRAP_CONTENT, + Gravity.CENTER)); + toggleButton.setBackgroundColor(Color.TRANSPARENT); + toggleButton.setImageResource(handleButtonDrawableId); + toggleButton.setOnClickListener(new OnClickListener() { + @Override + public void onClick(View v) { + toggle(); + } + }); + } + + private void setPosition(DockPosition position) { + this.position = position; + switch (position) { + case TOP: + setOrientation(LinearLayout.VERTICAL); + setGravity(Gravity.TOP); + break; + case RIGHT: + setOrientation(LinearLayout.HORIZONTAL); + setGravity(Gravity.RIGHT); + break; + case BOTTOM: + setOrientation(LinearLayout.VERTICAL); + setGravity(Gravity.BOTTOM); + break; + case LEFT: + setOrientation(LinearLayout.HORIZONTAL); + setGravity(Gravity.LEFT); + break; + } + } + + // ========================================= + // Public methods + // ========================================= + + public int getAnimationDuration() { + return animationDuration; + } + + public void setAnimationDuration(int milliseconds) { + animationDuration = milliseconds; + } + + public Boolean getIsRunning() { + return animationRunning; + } + + public void open() { + if (!animationRunning) { + Log.d(TAG, "Opening..."); + + Animation animation = createShowAnimation(); + this.setAnimation(animation); + animation.start(); + + isOpen = true; + } + } + + public void close() { + if (!animationRunning) { + Log.d(TAG, "Closing..."); + + Animation animation = createHideAnimation(); + this.setAnimation(animation); + animation.start(); + isOpen = false; + } + } + + public void toggle() { + if (isOpen) { + close(); + } else { + open(); + } + } + + // ========================================= + // Private methods + // ========================================= + + private Animation createHideAnimation() { + Animation animation = null; + switch (position) { + case TOP: + animation = new TranslateAnimation(0, 0, 0, -contentPlaceHolder + .getHeight()); + break; + case RIGHT: + animation = new TranslateAnimation(0, contentPlaceHolder + .getWidth(), 0, 0); + break; + case BOTTOM: + animation = new TranslateAnimation(0, 0, 0, contentPlaceHolder + .getHeight()); + break; + case LEFT: + animation = new TranslateAnimation(0, -contentPlaceHolder + .getWidth(), 0, 0); + break; + } + + animation.setDuration(animationDuration); + animation.setInterpolator(new AccelerateInterpolator()); + animation.setAnimationListener(new AnimationListener() { + @Override + public void onAnimationStart(Animation animation) { + animationRunning = true; + } + + @Override + public void onAnimationRepeat(Animation animation) { + } + + @Override + public void onAnimationEnd(Animation animation) { + contentPlaceHolder.setVisibility(View.GONE); + animationRunning = false; + } + }); + return animation; + } + + private Animation createShowAnimation() { + Animation animation = null; + switch (position) { + case TOP: + animation = new TranslateAnimation(0, 0, -contentPlaceHolder + .getHeight(), 0); + break; + case RIGHT: + animation = new TranslateAnimation(contentPlaceHolder.getWidth(), + 0, 0, 0); + break; + case BOTTOM: + animation = new TranslateAnimation(0, 0, contentPlaceHolder + .getHeight(), 0); + break; + case LEFT: + animation = new TranslateAnimation(-contentPlaceHolder.getWidth(), + 0, 0, 0); + break; + } + Log.d(TAG, "Animation duration: " + animationDuration); + animation.setDuration(animationDuration); + animation.setInterpolator(new DecelerateInterpolator()); + animation.setAnimationListener(new AnimationListener() { + @Override + public void onAnimationStart(Animation animation) { + animationRunning = true; + contentPlaceHolder.setVisibility(View.VISIBLE); + Log.d(TAG, "\"Show\" Animation started"); + } + + @Override + public void onAnimationRepeat(Animation animation) { + } + + @Override + public void onAnimationEnd(Animation animation) { + animationRunning = false; + Log.d(TAG, "\"Show\" Animation ended"); + } + }); + return animation; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPosition.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPosition.java new file mode 100644 index 000000000..59643dfc6 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DockPanel/DockPosition.java @@ -0,0 +1,5 @@ +package com.MobileAnarchy.Android.Widgets.DockPanel; + +public enum DockPosition { + TOP, BOTTOM, LEFT, RIGHT +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragAndDropManager.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragAndDropManager.java new file mode 100644 index 000000000..d7e0c5e44 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragAndDropManager.java @@ -0,0 +1,124 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import java.util.ArrayList; + +import android.content.Context; +import android.view.MotionEvent; +import android.view.View; +import android.view.View.OnTouchListener; + +public class DragAndDropManager { + + // ========================================= + // Private members + // ========================================= + + protected static final String TAG = "DragAndDropManager"; + private static DragAndDropManager instance = null; + private ArrayList dropZones; + private OnTouchListener originalTouchListener; + private DragSurface dragSurface; + private DraggableItem draggedItem; + private DropZone activeDropZone; + + // ========================================= + // Protected Constructor + // ========================================= + + protected DragAndDropManager() { + // Exists only to defeat instantiation. + dropZones = new ArrayList(); + } + + // ========================================= + // Public Properties + // ========================================= + + public static DragAndDropManager getInstance() { + if (instance == null) { + instance = new DragAndDropManager(); + } + return instance; + } + + public Context getContext() { + if (dragSurface == null) + return null; + + return dragSurface.getContext(); + } + + // ========================================= + // Public Methods + // ========================================= + + public void init(DragSurface surface) { + dragSurface = surface; + clearDropZones(); + } + + public void clearDropZones() { + dropZones.clear(); + } + + public void addDropZone(DropZone dropZone) { + dropZones.add(dropZone); + } + + + public void startDragging(OnTouchListener originalListener, DraggableItem draggedItem) { + originalTouchListener = originalListener; + this.draggedItem = draggedItem; + draggedItem.getSource().setOnTouchListener(new OnTouchListener() { + + @Override + public boolean onTouch(View v, MotionEvent event) { + int[] location = new int[2]; + v.getLocationOnScreen(location); + event.offsetLocation(location[0], location[1]); + invalidateDropZones((int)event.getX(), (int)event.getY()); + return dragSurface.onTouchEvent(event); + } + }); + + dragSurface.startDragging(draggedItem); + } + + + // ========================================= + // Protected Methods + // ========================================= + + protected void invalidateDropZones(int x, int y) { + if (activeDropZone != null) { + if (!activeDropZone.isOver(x, y)) { + activeDropZone.getListener().OnDragZoneLeft(activeDropZone, draggedItem); + activeDropZone = null; + } + else { + // we are still over the same drop zone, no need to check other drop zones + return; + } + } + + for (DropZone dropZone : dropZones) { + if (dropZone.isOver(x, y)) { + activeDropZone = dropZone; + dropZone.getListener().OnDragZoneEntered(activeDropZone, draggedItem); + break; + } + } + } + + protected void stoppedDragging() { + if (activeDropZone != null) { + activeDropZone.getListener().OnDropped(activeDropZone, draggedItem); + } + + // Registering the "old" listener to the view that initiated this drag session + draggedItem.getSource().setOnTouchListener(originalTouchListener); + draggedItem = null; + activeDropZone = null; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragSurface.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragSurface.java new file mode 100644 index 000000000..aebb9d481 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DragSurface.java @@ -0,0 +1,94 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import android.content.Context; +import android.util.AttributeSet; +import android.view.Gravity; +import android.view.MotionEvent; +import android.widget.FrameLayout; + +public class DragSurface extends FrameLayout { + + private float draggedViewHalfHeight; + private float draggedViewHalfWidth; + private int framesCount; + + private Boolean isDragging; + private DraggableItem draggedItem; + + public DragSurface(Context context, AttributeSet attrs) { + super(context, attrs); + isDragging = false; + } + + // ========================================= + // Touch Events Listener + // ========================================= + + @Override + public boolean onTouchEvent(MotionEvent event) { + if (isDragging && event.getAction() == MotionEvent.ACTION_UP) { + // Dragging ended + removeAllViews(); + isDragging = false; + + DragAndDropManager.getInstance().stoppedDragging(); + } + + if (isDragging && event.getAction() == MotionEvent.ACTION_MOVE) { + // Move the dragged view to it's new position + repositionView(event.getX(), event.getY()); + + // Mark this event as handled (so that other UI elements will not intercept it) + return true; + } + + return false; + } + + public void startDragging(DraggableItem draggableItem) { + this.draggedItem = draggableItem; + this.draggedItem.getDraggedView().setVisibility(INVISIBLE); + isDragging = true; + addView(this.draggedItem.getDraggedView()); + //repositionView(x, y); + framesCount = 0; + } + + private void repositionView(float x, float y) { + draggedViewHalfHeight = draggedItem.getDraggedView().getHeight() / 2f; + draggedViewHalfWidth = draggedItem.getDraggedView().getWidth() / 2f; + + // If the dragged view was not drawn yet, skip this phase + if (draggedViewHalfHeight == 0 || draggedViewHalfWidth == 0) + return; + + framesCount++; + + //Log.d(TAG, "Original = (x=" + x + ", y=" + y + ")"); + //Log.d(TAG, "Size (W=" + draggedViewHalfWidth + ", H=" + draggedViewHalfHeight + ")"); + + x = x - draggedViewHalfWidth; + y = y - draggedViewHalfHeight; + + x = Math.max(x, 0); + x = Math.min(x, getWidth() - draggedViewHalfWidth * 2); + + y = Math.max(y, 0); + y = Math.min(y, getHeight() - draggedViewHalfHeight * 2); + + //Log.d(TAG, "Moving view to (x=" + x + ", y=" + y + ")"); + FrameLayout.LayoutParams lp = new FrameLayout.LayoutParams(LayoutParams.WRAP_CONTENT, + LayoutParams.WRAP_CONTENT, Gravity.TOP + Gravity.LEFT); + + lp.setMargins((int)x, (int)y, 0, 0); + draggedItem.getDraggedView().setLayoutParams(lp); + + // hte first couple of dragged frame's positions are not calculated correctly, + // so we have a threshold before making the dragged view visible again + if (framesCount < 2) + return; + + draggedItem.getDraggedView().setVisibility(VISIBLE); + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableItem.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableItem.java new file mode 100644 index 000000000..d0c8b7e25 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableItem.java @@ -0,0 +1,44 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import android.view.View; + +public class DraggableItem { + + // ========================================= + // Private members + // ========================================= + + private View source; + private View draggedView; + private Object tag; + + // ========================================= + // Constructor + // ========================================= + + public DraggableItem(View source, View draggedItem) { + this.source = source; + this.draggedView = draggedItem; + } + + // ========================================= + // Public properties + // ========================================= + + public Object getTag() { + return tag; + } + + public void setTag(Object tag) { + this.tag = tag; + } + + public View getSource() { + return source; + } + + public View getDraggedView() { + return draggedView; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableViewsFactory.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableViewsFactory.java new file mode 100644 index 000000000..246b2392f --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DraggableViewsFactory.java @@ -0,0 +1,19 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import android.content.Context; +import android.view.View; +import android.widget.TextView; +import android.widget.TableLayout.LayoutParams; + +public class DraggableViewsFactory { + + public static View getLabel(String text) { + Context context = DragAndDropManager.getInstance().getContext(); + TextView textView = new TextView(context); + textView.setText(text); + textView.setLayoutParams(new LayoutParams(LayoutParams.WRAP_CONTENT, LayoutParams.WRAP_CONTENT)); + //textView.setGravity(Gravity.TOP + Gravity.LEFT); + return textView; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZone.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZone.java new file mode 100644 index 000000000..06a8caa17 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZone.java @@ -0,0 +1,67 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +import android.view.View; + +public class DropZone { + + // ========================================= + // Private members + // ========================================= + + private View view; + private DropZoneEventsListener listener; + private int left, top, width, height; + private Boolean dimansionsCalculated; + + // ========================================= + // Constructor + // ========================================= + + public DropZone(View view, DropZoneEventsListener listener) { + this.view = view; + this.listener = listener; + dimansionsCalculated = false; + } + + // ========================================= + // Public properties + // ========================================= + + public View getView() { + return view; + } + + // ========================================= + // Public methods + // ========================================= + + public Boolean isOver(int x, int y) { + if (!dimansionsCalculated) + calculateDimensions(); + + Boolean isOver = (x >= left && x <= (left + width)) && + (y >= top && y <= (top + height)); + + //Log.d("DragZone", "x=" +x + ", left=" + left + ", y=" + y + ", top=" + top + " width=" + width + ", height=" + height + ", isover=" + isOver); + + return isOver; + } + + // ========================================= + // Protected & Private methods + // ========================================= + + protected DropZoneEventsListener getListener() { + return listener; + } + + private void calculateDimensions() { + int[] location = new int[2]; + view.getLocationOnScreen(location); + left = location[0]; + top = location[1]; + width = view.getWidth(); + height = view.getHeight(); + dimansionsCalculated = true; + } +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZoneEventsListener.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZoneEventsListener.java new file mode 100644 index 000000000..828a1cbf2 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/DragAndDrop/DropZoneEventsListener.java @@ -0,0 +1,9 @@ +package com.MobileAnarchy.Android.Widgets.DragAndDrop; + +public interface DropZoneEventsListener { + + void OnDragZoneEntered(DropZone zone, DraggableItem item); + void OnDragZoneLeft(DropZone zone, DraggableItem item); + void OnDropped(DropZone zone, DraggableItem item); + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/DualJoystickView.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/DualJoystickView.java new file mode 100644 index 000000000..bb419d404 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/DualJoystickView.java @@ -0,0 +1,147 @@ +package com.MobileAnarchy.Android.Widgets.Joystick; + +import android.content.Context; +import android.graphics.Canvas; +import android.graphics.Color; +import android.graphics.Paint; +import android.util.AttributeSet; +import android.view.MotionEvent; +import android.view.View; +import android.view.ViewGroup; +import android.widget.LinearLayout; + +public class DualJoystickView extends LinearLayout { + @SuppressWarnings("unused") + private static final String TAG = DualJoystickView.class.getSimpleName(); + + private final boolean D = false; + private Paint dbgPaint1; + + private JoystickView stickL; + private JoystickView stickR; + + private View pad; + + public DualJoystickView(Context context) { + super(context); + stickL = new JoystickView(context); + stickR = new JoystickView(context); + initDualJoystickView(); + } + + public DualJoystickView(Context context, AttributeSet attrs) { + super(context, attrs); + stickL = new JoystickView(context, attrs); + stickR = new JoystickView(context, attrs); + initDualJoystickView(); + } + + private void initDualJoystickView() { + setOrientation(LinearLayout.HORIZONTAL); + + if ( D ) { + dbgPaint1 = new Paint(Paint.ANTI_ALIAS_FLAG); + dbgPaint1.setColor(Color.CYAN); + dbgPaint1.setStrokeWidth(1); + dbgPaint1.setStyle(Paint.Style.STROKE); + } + + pad = new View(getContext()); + } + + @Override + protected void onMeasure(int widthMeasureSpec, int heightMeasureSpec) { + super.onMeasure(widthMeasureSpec, heightMeasureSpec); + removeView(stickL); + removeView(stickR); + + float padW = getMeasuredWidth()-(getMeasuredHeight()*2); + int joyWidth = (int) ((getMeasuredWidth()-padW)/2); + LayoutParams joyLParams = new LayoutParams(joyWidth,getMeasuredHeight()); + + stickL.setLayoutParams(joyLParams); + stickR.setLayoutParams(joyLParams); + + stickL.TAG = "L"; + stickR.TAG = "R"; + stickL.setPointerId(JoystickView.INVALID_POINTER_ID); + stickR.setPointerId(JoystickView.INVALID_POINTER_ID); + + addView(stickL); + + ViewGroup.LayoutParams padLParams = new ViewGroup.LayoutParams((int) padW,getMeasuredHeight()); + removeView(pad); + pad.setLayoutParams(padLParams); + addView(pad); + + addView(stickR); + } + + @Override + protected void onLayout(boolean changed, int l, int t, int r, int b) { + super.onLayout(changed, l, t, r, b); + stickR.setTouchOffset(stickR.getLeft(), stickR.getTop()); + } + + public void setAutoReturnToCenter(boolean left, boolean right) { + stickL.setAutoReturnToCenter(left); + stickR.setAutoReturnToCenter(right); + } + + public void setOnJostickMovedListener(JoystickMovedListener left, JoystickMovedListener right) { + stickL.setOnJostickMovedListener(left); + stickR.setOnJostickMovedListener(right); + } + + public void setOnJostickClickedListener(JoystickClickedListener left, JoystickClickedListener right) { + stickL.setOnJostickClickedListener(left); + stickR.setOnJostickClickedListener(right); + } + + public void setYAxisInverted(boolean leftYAxisInverted, boolean rightYAxisInverted) { + stickL.setYAxisInverted(leftYAxisInverted); + stickL.setYAxisInverted(rightYAxisInverted); + } + + public void setMovementConstraint(int movementConstraint) { + stickL.setMovementConstraint(movementConstraint); + stickR.setMovementConstraint(movementConstraint); + } + + public void setMovementRange(float movementRangeLeft, float movementRangeRight) { + stickL.setMovementRange(movementRangeLeft); + stickR.setMovementRange(movementRangeRight); + } + + public void setMoveResolution(float leftMoveResolution, float rightMoveResolution) { + stickL.setMoveResolution(leftMoveResolution); + stickR.setMoveResolution(rightMoveResolution); + } + + public void setUserCoordinateSystem(int leftCoordinateSystem, int rightCoordinateSystem) { + stickL.setUserCoordinateSystem(leftCoordinateSystem); + stickR.setUserCoordinateSystem(rightCoordinateSystem); + } + + @Override + protected void dispatchDraw(Canvas canvas) { + super.dispatchDraw(canvas); + if (D) { + canvas.drawRect(1, 1, getMeasuredWidth()-1, getMeasuredHeight()-1, dbgPaint1); + } + } + + @Override + public boolean dispatchTouchEvent(MotionEvent ev) { + boolean l = stickL.dispatchTouchEvent(ev); + boolean r = stickR.dispatchTouchEvent(ev); + return l || r; + } + + @Override + public boolean onTouchEvent(MotionEvent ev) { + boolean l = stickL.onTouchEvent(ev); + boolean r = stickR.onTouchEvent(ev); + return l || r; + } +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickClickedListener.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickClickedListener.java new file mode 100644 index 000000000..128828980 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickClickedListener.java @@ -0,0 +1,6 @@ +package com.MobileAnarchy.Android.Widgets.Joystick; + +public interface JoystickClickedListener { + public void OnClicked(); + public void OnReleased(); +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickMovedListener.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickMovedListener.java new file mode 100644 index 000000000..346f2efed --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickMovedListener.java @@ -0,0 +1,7 @@ +package com.MobileAnarchy.Android.Widgets.Joystick; + +public interface JoystickMovedListener { + public void OnMoved(int pan, int tilt); + public void OnReleased(); + public void OnReturnedToCenter(); +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickView.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickView.java new file mode 100644 index 000000000..bab74e5a7 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/Joystick/JoystickView.java @@ -0,0 +1,521 @@ +package com.MobileAnarchy.Android.Widgets.Joystick; + +import android.content.Context; +import android.graphics.Canvas; +import android.graphics.Color; +import android.graphics.Paint; +import android.os.Handler; +import android.util.AttributeSet; +import android.util.Log; +import android.view.HapticFeedbackConstants; +import android.view.MotionEvent; +import android.view.View; + +public class JoystickView extends View { + public static final int INVALID_POINTER_ID = -1; + + // ========================================= + // Private Members + // ========================================= + private final boolean D = false; + String TAG = "JoystickView"; + + private Paint dbgPaint1; + private Paint dbgPaint2; + + private Paint bgPaint; + private Paint handlePaint; + + private int innerPadding; + private int bgRadius; + private int handleRadius; + private int movementRadius; + private int handleInnerBoundaries; + + private JoystickMovedListener moveListener; + private JoystickClickedListener clickListener; + + //# of pixels movement required between reporting to the listener + private float moveResolution; + + private boolean yAxisInverted; + private boolean autoReturnToCenter; + + //Max range of movement in user coordinate system + public final static int CONSTRAIN_BOX = 0; + public final static int CONSTRAIN_CIRCLE = 1; + private int movementConstraint; + private float movementRange; + + public final static int COORDINATE_CARTESIAN = 0; //Regular cartesian coordinates + public final static int COORDINATE_DIFFERENTIAL = 1; //Uses polar rotation of 45 degrees to calc differential drive paramaters + private int userCoordinateSystem; + + //Records touch pressure for click handling + private float touchPressure; + private boolean clicked; + private float clickThreshold; + + //Last touch point in view coordinates + private int pointerId = INVALID_POINTER_ID; + private float touchX, touchY; + + //Last reported position in view coordinates (allows different reporting sensitivities) + private float reportX, reportY; + + //Handle center in view coordinates + private float handleX, handleY; + + //Center of the view in view coordinates + private int cX, cY; + + //Size of the view in view coordinates + private int dimX, dimY; + + //Cartesian coordinates of last touch point - joystick center is (0,0) + private int cartX, cartY; + + //Polar coordinates of the touch point from joystick center + private double radial; + private double angle; + + //User coordinates of last touch point + private int userX, userY; + + //Offset co-ordinates (used when touch events are received from parent's coordinate origin) + private int offsetX; + private int offsetY; + + // ========================================= + // Constructors + // ========================================= + + public JoystickView(Context context) { + super(context); + initJoystickView(); + } + + public JoystickView(Context context, AttributeSet attrs) { + super(context, attrs); + initJoystickView(); + } + + public JoystickView(Context context, AttributeSet attrs, int defStyle) { + super(context, attrs, defStyle); + initJoystickView(); + } + + // ========================================= + // Initialization + // ========================================= + + private void initJoystickView() { + setFocusable(true); + + dbgPaint1 = new Paint(Paint.ANTI_ALIAS_FLAG); + dbgPaint1.setColor(Color.RED); + dbgPaint1.setStrokeWidth(1); + dbgPaint1.setStyle(Paint.Style.STROKE); + + dbgPaint2 = new Paint(Paint.ANTI_ALIAS_FLAG); + dbgPaint2.setColor(Color.GREEN); + dbgPaint2.setStrokeWidth(1); + dbgPaint2.setStyle(Paint.Style.STROKE); + + bgPaint = new Paint(Paint.ANTI_ALIAS_FLAG); + bgPaint.setColor(Color.GRAY); + bgPaint.setStrokeWidth(1); + bgPaint.setStyle(Paint.Style.FILL_AND_STROKE); + + handlePaint = new Paint(Paint.ANTI_ALIAS_FLAG); + handlePaint.setColor(Color.DKGRAY); + handlePaint.setStrokeWidth(1); + handlePaint.setStyle(Paint.Style.FILL_AND_STROKE); + + innerPadding = 10; + + setMovementRange(10); + setMoveResolution(1.0f); + setClickThreshold(0.4f); + setYAxisInverted(true); + setUserCoordinateSystem(COORDINATE_CARTESIAN); + setAutoReturnToCenter(true); + } + + public void setAutoReturnToCenter(boolean autoReturnToCenter) { + this.autoReturnToCenter = autoReturnToCenter; + } + + public boolean isAutoReturnToCenter() { + return autoReturnToCenter; + } + + public void setUserCoordinateSystem(int userCoordinateSystem) { + if (userCoordinateSystem < COORDINATE_CARTESIAN || movementConstraint > COORDINATE_DIFFERENTIAL) + Log.e(TAG, "invalid value for userCoordinateSystem"); + else + this.userCoordinateSystem = userCoordinateSystem; + } + + public int getUserCoordinateSystem() { + return userCoordinateSystem; + } + + public void setMovementConstraint(int movementConstraint) { + if (movementConstraint < CONSTRAIN_BOX || movementConstraint > CONSTRAIN_CIRCLE) + Log.e(TAG, "invalid value for movementConstraint"); + else + this.movementConstraint = movementConstraint; + } + + public int getMovementConstraint() { + return movementConstraint; + } + + public boolean isYAxisInverted() { + return yAxisInverted; + } + + public void setYAxisInverted(boolean yAxisInverted) { + this.yAxisInverted = yAxisInverted; + } + + /** + * Set the pressure sensitivity for registering a click + * @param clickThreshold threshold 0...1.0f inclusive. 0 will cause clicks to never be reported, 1.0 is a very hard click + */ + public void setClickThreshold(float clickThreshold) { + if (clickThreshold < 0 || clickThreshold > 1.0f) + Log.e(TAG, "clickThreshold must range from 0...1.0f inclusive"); + else + this.clickThreshold = clickThreshold; + } + + public float getClickThreshold() { + return clickThreshold; + } + + public void setMovementRange(float movementRange) { + this.movementRange = movementRange; + } + + public float getMovementRange() { + return movementRange; + } + + public void setMoveResolution(float moveResolution) { + this.moveResolution = moveResolution; + } + + public float getMoveResolution() { + return moveResolution; + } + + // ========================================= + // Public Methods + // ========================================= + + public void setOnJostickMovedListener(JoystickMovedListener listener) { + this.moveListener = listener; + } + + public void setOnJostickClickedListener(JoystickClickedListener listener) { + this.clickListener = listener; + } + + // ========================================= + // Drawing Functionality + // ========================================= + + @Override + protected void onMeasure(int widthMeasureSpec, int heightMeasureSpec) { + // Here we make sure that we have a perfect circle + int measuredWidth = measure(widthMeasureSpec); + int measuredHeight = measure(heightMeasureSpec); + setMeasuredDimension(measuredWidth, measuredHeight); + } + + @Override + protected void onLayout(boolean changed, int left, int top, int right, int bottom) { + super.onLayout(changed, left, top, right, bottom); + + int d = Math.min(getMeasuredWidth(), getMeasuredHeight()); + + dimX = d; + dimY = d; + + cX = d / 2; + cY = d / 2; + + bgRadius = dimX/2 - innerPadding; + handleRadius = (int)(d * 0.25); + handleInnerBoundaries = handleRadius; + movementRadius = Math.min(cX, cY) - handleInnerBoundaries; + } + + private int measure(int measureSpec) { + int result = 0; + // Decode the measurement specifications. + int specMode = MeasureSpec.getMode(measureSpec); + int specSize = MeasureSpec.getSize(measureSpec); + if (specMode == MeasureSpec.UNSPECIFIED) { + // Return a default size of 200 if no bounds are specified. + result = 200; + } else { + // As you want to fill the available space + // always return the full available bounds. + result = specSize; + } + return result; + } + + @Override + protected void onDraw(Canvas canvas) { + canvas.save(); + // Draw the background + canvas.drawCircle(cX, cY, bgRadius, bgPaint); + + // Draw the handle + handleX = touchX + cX; + handleY = touchY + cY; + canvas.drawCircle(handleX, handleY, handleRadius, handlePaint); + + if (D) { + canvas.drawRect(1, 1, getMeasuredWidth()-1, getMeasuredHeight()-1, dbgPaint1); + + canvas.drawCircle(handleX, handleY, 3, dbgPaint1); + + if ( movementConstraint == CONSTRAIN_CIRCLE ) { + canvas.drawCircle(cX, cY, this.movementRadius, dbgPaint1); + } + else { + canvas.drawRect(cX-movementRadius, cY-movementRadius, cX+movementRadius, cY+movementRadius, dbgPaint1); + } + + //Origin to touch point + canvas.drawLine(cX, cY, handleX, handleY, dbgPaint2); + + int baseY = (int) (touchY < 0 ? cY + handleRadius : cY - handleRadius); + canvas.drawText(String.format("%s (%.0f,%.0f)", TAG, touchX, touchY), handleX-20, baseY-7, dbgPaint2); + canvas.drawText("("+ String.format("%.0f, %.1f", radial, angle * 57.2957795) + (char) 0x00B0 + ")", handleX-20, baseY+15, dbgPaint2); + } + +// Log.d(TAG, String.format("touch(%f,%f)", touchX, touchY)); +// Log.d(TAG, String.format("onDraw(%.1f,%.1f)\n\n", handleX, handleY)); + canvas.restore(); + } + + // Constrain touch within a box + private void constrainBox() { + touchX = Math.max(Math.min(touchX, movementRadius), -movementRadius); + touchY = Math.max(Math.min(touchY, movementRadius), -movementRadius); + } + + // Constrain touch within a circle + private void constrainCircle() { + float diffX = touchX; + float diffY = touchY; + double radial = Math.sqrt((diffX*diffX) + (diffY*diffY)); + if ( radial > movementRadius ) { + touchX = (int)((diffX / radial) * movementRadius); + touchY = (int)((diffY / radial) * movementRadius); + } + } + + public void setPointerId(int id) { + this.pointerId = id; + } + + public int getPointerId() { + return pointerId; + } + + @Override + public boolean onTouchEvent(MotionEvent ev) { + final int action = ev.getAction(); + switch (action & MotionEvent.ACTION_MASK) { + case MotionEvent.ACTION_MOVE: { + return processMoveEvent(ev); + } + case MotionEvent.ACTION_CANCEL: + case MotionEvent.ACTION_UP: { + if ( pointerId != INVALID_POINTER_ID ) { +// Log.d(TAG, "ACTION_UP"); + returnHandleToCenter(); + setPointerId(INVALID_POINTER_ID); + } + break; + } + case MotionEvent.ACTION_POINTER_UP: { + if ( pointerId != INVALID_POINTER_ID ) { + final int pointerIndex = (action & MotionEvent.ACTION_POINTER_INDEX_MASK) >> MotionEvent.ACTION_POINTER_INDEX_SHIFT; + final int pointerId = ev.getPointerId(pointerIndex); + if ( pointerId == this.pointerId ) { +// Log.d(TAG, "ACTION_POINTER_UP: " + pointerId); + returnHandleToCenter(); + setPointerId(INVALID_POINTER_ID); + return true; + } + } + break; + } + case MotionEvent.ACTION_DOWN: { + if ( pointerId == INVALID_POINTER_ID ) { + int x = (int) ev.getX(); + if ( x >= offsetX && x < offsetX + dimX ) { + setPointerId(ev.getPointerId(0)); +// Log.d(TAG, "ACTION_DOWN: " + getPointerId()); + return true; + } + } + break; + } + case MotionEvent.ACTION_POINTER_DOWN: { + if ( pointerId == INVALID_POINTER_ID ) { + final int pointerIndex = (action & MotionEvent.ACTION_POINTER_INDEX_MASK) >> MotionEvent.ACTION_POINTER_INDEX_SHIFT; + final int pointerId = ev.getPointerId(pointerIndex); + int x = (int) ev.getX(pointerId); + if ( x >= offsetX && x < offsetX + dimX ) { +// Log.d(TAG, "ACTION_POINTER_DOWN: " + pointerId); + setPointerId(pointerId); + return true; + } + } + break; + } + } + return false; + } + + private boolean processMoveEvent(MotionEvent ev) { + if ( pointerId != INVALID_POINTER_ID ) { + final int pointerIndex = ev.findPointerIndex(pointerId); + + // Translate touch position to center of view + float x = ev.getX(pointerIndex); + touchX = x - cX - offsetX; + float y = ev.getY(pointerIndex); + touchY = y - cY - offsetY; + +// Log.d(TAG, String.format("ACTION_MOVE: (%03.0f, %03.0f) => (%03.0f, %03.0f)", x, y, touchX, touchY)); + + reportOnMoved(); + invalidate(); + + touchPressure = ev.getPressure(pointerIndex); + reportOnPressure(); + + return true; + } + return false; + } + + private void reportOnMoved() { + if ( movementConstraint == CONSTRAIN_CIRCLE ) + constrainCircle(); + else + constrainBox(); + + calcUserCoordinates(); + + if (moveListener != null) { + boolean rx = Math.abs(touchX - reportX) >= moveResolution; + boolean ry = Math.abs(touchY - reportY) >= moveResolution; + if (rx || ry) { + this.reportX = touchX; + this.reportY = touchY; + +// Log.d(TAG, String.format("moveListener.OnMoved(%d,%d)", (int)userX, (int)userY)); + moveListener.OnMoved(userX, userY); + } + } + } + + private void calcUserCoordinates() { + //First convert to cartesian coordinates + cartX = (int)(touchX / movementRadius * movementRange); + cartY = (int)(touchY / movementRadius * movementRange); + + radial = Math.sqrt((cartX*cartX) + (cartY*cartY)); + angle = Math.atan2(cartY, cartX); + + //Invert Y axis if requested + if ( !yAxisInverted ) + cartY *= -1; + + if ( userCoordinateSystem == COORDINATE_CARTESIAN ) { + userX = cartX; + userY = cartY; + } + else if ( userCoordinateSystem == COORDINATE_DIFFERENTIAL ) { + userX = cartY + cartX / 4; + userY = cartY - cartX / 4; + + if ( userX < -movementRange ) + userX = (int)-movementRange; + if ( userX > movementRange ) + userX = (int)movementRange; + + if ( userY < -movementRange ) + userY = (int)-movementRange; + if ( userY > movementRange ) + userY = (int)movementRange; + } + + } + + //Simple pressure click + private void reportOnPressure() { +// Log.d(TAG, String.format("touchPressure=%.2f", this.touchPressure)); + if ( clickListener != null ) { + if ( clicked && touchPressure < clickThreshold ) { + clickListener.OnReleased(); + this.clicked = false; +// Log.d(TAG, "reset click"); + invalidate(); + } + else if ( !clicked && touchPressure >= clickThreshold ) { + clicked = true; + clickListener.OnClicked(); +// Log.d(TAG, "click"); + invalidate(); + performHapticFeedback(HapticFeedbackConstants.VIRTUAL_KEY); + } + } + } + + private void returnHandleToCenter() { + if ( autoReturnToCenter ) { + final int numberOfFrames = 5; + final double intervalsX = (0 - touchX) / numberOfFrames; + final double intervalsY = (0 - touchY) / numberOfFrames; + + for (int i = 0; i < numberOfFrames; i++) { + final int j = i; + postDelayed(new Runnable() { + @Override + public void run() { + touchX += intervalsX; + touchY += intervalsY; + + reportOnMoved(); + invalidate(); + + if (moveListener != null && j == numberOfFrames - 1) { + moveListener.OnReturnedToCenter(); + } + } + }, i * 40); + } + + if (moveListener != null) { + moveListener.OnReleased(); + } + } + } + + public void setTouchOffset(int x, int y) { + offsetX = x; + offsetY = y; + } +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdEditText.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdEditText.java new file mode 100644 index 000000000..5fbd76f46 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdEditText.java @@ -0,0 +1,169 @@ +package com.MobileAnarchy.Android.Widgets.ThresholdEditText; + +import android.content.Context; +import android.os.Handler; +import android.text.Editable; +import android.text.TextWatcher; +import android.util.AttributeSet; +import android.widget.EditText; + +public class ThresholdEditText extends EditText { + + // ========================================= + // Private members + // ========================================= + + private int threshold; + private ThresholdTextChanged thresholdTextChanged; + private Handler handler; + private Runnable invoker; + private boolean thresholdDisabledOnEmptyInput; + + + // ========================================= + // Constructors + // ========================================= + + public ThresholdEditText(Context context) { + super(context); + initAttributes(null); + init(); + } + + public ThresholdEditText(Context context, AttributeSet attrs) { + super(context, attrs); + initAttributes(attrs); + init(); + } + + + // ========================================= + // Public properties + // ========================================= + + /** + * Get the current threshold value + */ + public int getThreshold() { + return threshold; + } + + /** + * Set the threshold value (in milliseconds) + * + * @param threshold + * Threshold value + */ + public void setThreshold(int threshold) { + this.threshold = threshold; + } + + /** + * @return True = the callback will fire immediately when the content of the + * EditText is emptied False = The threshold will be used even on + * empty input + */ + public boolean getThresholdDisabledOnEmptyInput() { + return thresholdDisabledOnEmptyInput; + } + + /** + * @param thresholdDisabledOnEmptyInput + * Set to true if you want the callback to fire immediately when + * the content of the EditText is emptied + */ + public void setThresholdDisabledOnEmptyInput( + boolean thresholdDisabledOnEmptyInput) { + this.thresholdDisabledOnEmptyInput = thresholdDisabledOnEmptyInput; + } + + /** + * Set the callback to the OnThresholdTextChanged event + * + * @param listener + */ + public void setOnThresholdTextChanged(ThresholdTextChanged listener) { + this.thresholdTextChanged = listener; + } + + // ========================================= + // Private / Protected methods + // ========================================= + + /** + * Load properties values from xml layout + */ + private void initAttributes(AttributeSet attrs) { + if (attrs != null) { + String namespace = "http://com.MobileAnarchy.Android.Widgets"; + + // Load values to local members + this.threshold = attrs.getAttributeIntValue(namespace, "threshold", + 500); + this.thresholdDisabledOnEmptyInput = attrs.getAttributeBooleanValue( + namespace, "disableThresholdOnEmptyInput", true); + } else { + // Default threshold value is 0.5 seconds + threshold = 500; + + // Default behaviour on emptied text - no threshold + thresholdDisabledOnEmptyInput = true; + } + } + + /** + * Initialize the private members with default values + */ + private void init() { + + handler = new Handler(); + + invoker = new Runnable() { + + @Override + public void run() { + invokeCallback(); + } + + }; + + this.addTextChangedListener(new TextWatcher() { + + @Override + public void afterTextChanged(Editable s) { + } + + @Override + public void beforeTextChanged(CharSequence s, int start, int count, + int after) { + } + + @Override + public void onTextChanged(CharSequence s, int start, int before, + int count) { + + // Remove any existing pending callbacks + handler.removeCallbacks(invoker); + + if (s.length() == 0 && thresholdDisabledOnEmptyInput) { + // The text is empty, so invoke the callback immediately + invoker.run(); + } else { + // Post a new delayed callback + handler.postDelayed(invoker, threshold); + } + } + + }); + } + + /** + * Invoking the callback on the listener provided (if provided) + */ + private void invokeCallback() { + if (thresholdTextChanged != null) { + thresholdTextChanged.onThersholdTextChanged(this.getText()); + } + } + +} \ No newline at end of file diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdTextChanged.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdTextChanged.java new file mode 100644 index 000000000..145f6547b --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/ThresholdEditText/ThresholdTextChanged.java @@ -0,0 +1,7 @@ +package com.MobileAnarchy.Android.Widgets.ThresholdEditText; + +import android.text.Editable; + +public interface ThresholdTextChanged { + void onThersholdTextChanged(Editable text); +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/SingleTileLayout.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/SingleTileLayout.java new file mode 100644 index 000000000..d2f3be2d3 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/SingleTileLayout.java @@ -0,0 +1,68 @@ +package com.MobileAnarchy.Android.Widgets.TilesLayout; + +import android.content.Context; +import android.util.AttributeSet; +import android.view.View; +import android.widget.FrameLayout; + +public class SingleTileLayout extends FrameLayout { + + // ========================================= + // Private members + // ========================================= + + private TilePosition position; + private long timestamp; + + // ========================================= + // Constructors + // ========================================= + + public SingleTileLayout(Context context) { + super(context); + } + + public SingleTileLayout(Context context, AttributeSet attrs) { + super(context, attrs); + } + + + // ========================================= + // Public Methods + // ========================================= + + public TilePosition getPosition() { + return position; + } + + public void setPosition(TilePosition position) { + this.position = position; + } + + public long getTimestamp() { + return this.timestamp; + } + + // ========================================= + // Overrides + // ========================================= + + @Override + public void addView(View child) { + super.addView(child); + timestamp = java.lang.System.currentTimeMillis(); + } + + @Override + public void removeAllViews() { + super.removeAllViews(); + timestamp = 0; + } + + @Override + public void removeView(View view) { + super.removeView(view); + timestamp = 0; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilePosition.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilePosition.java new file mode 100644 index 000000000..04bf0c1d4 --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilePosition.java @@ -0,0 +1,63 @@ +package com.MobileAnarchy.Android.Widgets.TilesLayout; + + +public class TilePosition { + + // ========================================= + // Private Members + // ========================================= + + private float x, y, height, width; + + // ========================================= + // Constructors + // ========================================= + + public TilePosition(float x, float y, float width, float height) { + this.x = x; + this.y = y; + this.height = height; + this.width = width; + } + + // ========================================= + // Public Properties + // ========================================= + + public float getX() { + return x; + } + + public float getY() { + return y; + } + + public float getHeight() { + return height; + } + + public float getWidth() { + return width; + } + + + // ========================================= + // Public Methods + // ========================================= + + public Boolean equals(TilePosition position) { + if (position == null) + return false; + + return this.x == position.x && + this.y == position.y && + this.height == position.height && + this.width == position.width; + } + + @Override + public String toString() { + return "TilePosition = [X: " + x + ", Y: " + y + ", Height: " + height + ", Width: " + width + "]"; + } + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayout.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayout.java new file mode 100644 index 000000000..c1728faff --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayout.java @@ -0,0 +1,299 @@ +package com.MobileAnarchy.Android.Widgets.TilesLayout; + +import java.util.ArrayList; +import java.util.List; + +import android.R; +import android.content.Context; +import android.graphics.Color; +import android.os.Handler; +import android.util.AttributeSet; +import android.util.Log; +import android.view.Gravity; +import android.view.View; +import android.view.animation.AlphaAnimation; +import android.view.animation.Animation; +import android.view.animation.AnimationSet; +import android.view.animation.DecelerateInterpolator; +import android.view.animation.ScaleAnimation; +import android.view.animation.TranslateAnimation; +import android.view.animation.Animation.AnimationListener; +import android.widget.FrameLayout; + +public class TilesLayout extends FrameLayout { + + // ========================================= + // Private members + // ========================================= + + private static final String TAG = "TilesLayout"; + private int animatedTransitionDuration; + private List tiles; + private TilesLayoutPreset preset; + private int tileBackgroundResourceId; + + // ========================================= + // Constructors + // ========================================= + + public TilesLayout(Context context) { + super(context); + Init(null); + } + + public TilesLayout(Context context, AttributeSet attrs) { + super(context, attrs); + Init(attrs); + } + + + // ========================================= + // Public Properties + // ========================================= + + public void setPreset(TilesLayoutPreset preset) { + try { + rebuildLayout(preset); + this.preset = preset; + } + catch (Exception ex) { + Log.e(TAG, "Failed to set layout preset", ex); + } + } + + public TilesLayoutPreset getPreset() { + return this.preset; + } + + public int getAnimatedTransitionDuration() { + return animatedTransitionDuration; + } + + public void setAnimatedTransitionDuration(int animatedTransitionDuration) { + this.animatedTransitionDuration = animatedTransitionDuration; + } + + public int getTileBackgroundResourceId() { + return tileBackgroundResourceId; + } + + public void setTileBackgroundResourceId(int tileBackgroundResourceId) { + this.tileBackgroundResourceId = tileBackgroundResourceId; + } + + // ========================================= + // Public Methods + // ========================================= + + public void addContent(View view) { + for (int i = 0; i < tiles.size(); i++) { + if (tiles.get(i).getChildCount() == 0) { + tiles.get(i).addView(view); + return; + } + } + // No available space for the new view... + // TODO: Take the tile with the smallest time stamp and place the new view in it + } + + public void clearView(int tileId) { + if (tiles.size() < tileId) { + tiles.get(tileId).removeAllViews(); + } + } + + // ========================================= + // Private Methods + // ========================================= + + private void Init(AttributeSet attrs) { + animatedTransitionDuration = 750; + tileBackgroundResourceId = R.drawable.edit_text; + tiles = new ArrayList(); + } + + + private void rebuildLayout(TilesLayoutPreset preset) { + ArrayList positions = buildViewsPositions(preset); + + // We need to transform the current layout, to the new layout + int extraViews = tiles.size() - positions.size(); + if (extraViews > 0) { + // Remove the extra views + while(tiles.size() - positions.size() > 0) { + int lastViewPosition = tiles.size() - 1; + removeView(tiles.get(lastViewPosition)); + tiles.remove(lastViewPosition); + } + } else { + // Add the extra views + for (int i = tiles.size(); i< positions.size(); i++) { + TilePosition newTilePosition = positions.get(i); + SingleTileLayout tile = new SingleTileLayout(getContext()); + tile.setBackgroundResource(tileBackgroundResourceId); + + FrameLayout.LayoutParams lp = new FrameLayout.LayoutParams( + (int)newTilePosition.getWidth(), + (int)newTilePosition.getHeight(), + Gravity.TOP + Gravity.LEFT); + lp.setMargins((int)newTilePosition.getX(), + (int)newTilePosition.getY(), 0, 0); + + tile.setLayoutParams(lp); + + tiles.add(tile); + addView(tile); + } + } + // There is a bug in the animation-set, so we'll not animate + animateChange(positions); + + // Regular repositioning (no animation) + //processChange(positions); + } + + + + private ArrayList buildViewsPositions(TilesLayoutPreset preset) { + int width = getWidth(); + int height = getHeight(); + + Log.d(TAG, "Container's Dimensions = Width: " + width + ", Height: " + height); + ArrayList actualPositions = new ArrayList(); + for (TilePosition position : preset.getTilePositions()) { + + int tileX = (int) Math.round(width * ((float)position.getX() / 100.0)); + int tileY = (int) Math.round(height * ((float)position.getY() / 100.0)); + int tileWidth = (int) Math.round(width * ((float)position.getWidth() / 100.0)); + int tileHeight = (int) Math.round(height * ((float)position.getHeight() / 100.0)); + + TilePosition actualPosition = new TilePosition(tileX, tileY, tileWidth, tileHeight); + actualPositions.add(actualPosition); + + Log.d(TAG, "New tile created - X: " + tileX + ", Y: " + tileY + ", Width: " + tileWidth + ", Height: " + tileHeight); + } + return actualPositions; + } + + + @SuppressWarnings("unused") + private void processChange(ArrayList positions) { + for (int i = 0; i < tiles.size(); i++) { + final SingleTileLayout currentTile = tiles.get(i); + final TilePosition targetPosition = positions.get(i); + currentTile.setPosition(targetPosition); + + FrameLayout.LayoutParams lp = new FrameLayout.LayoutParams( + (int)targetPosition.getWidth(), + (int)targetPosition.getHeight(), + Gravity.TOP + Gravity.LEFT); + lp.setMargins((int)targetPosition.getX(), + (int)targetPosition.getY(), 0, 0); + + currentTile.setLayoutParams(lp); + } + } + + + private void animateChange(ArrayList positions) { + AnimationSet animationSet = new AnimationSet(true); + DecelerateInterpolator decelerateInterpolator = new DecelerateInterpolator(); + + for (int i = 0; i < tiles.size(); i++) { + AnimationSet scaleAndMove = new AnimationSet(true); + scaleAndMove.setFillAfter(true); + + final SingleTileLayout currentTile = tiles.get(i); + TilePosition currentPosition = currentTile.getPosition(); + final TilePosition targetPosition = positions.get(i); + + if (currentPosition == null) { + AlphaAnimation alphaAnimation = new AlphaAnimation(0, 1); + alphaAnimation.setDuration(animatedTransitionDuration); + alphaAnimation.setStartOffset(0); + currentTile.setAnimation(alphaAnimation); + + scaleAndMove.addAnimation(alphaAnimation); + } + + currentTile.setPosition(targetPosition); + + if (!targetPosition.equals(currentPosition)) { + float toXDelta = 0, toYDelta = 0; + if (currentPosition != null) { + // Calculate new position + toXDelta = targetPosition.getX() - currentPosition.getX(); + toYDelta = targetPosition.getY() - currentPosition.getY(); + + // Factor in the scaling animation + toXDelta = toXDelta / (targetPosition.getWidth() / currentPosition.getWidth()); + toYDelta = toYDelta / (targetPosition.getHeight() / currentPosition.getHeight()); + } + + // Move + TranslateAnimation moveAnimation = new TranslateAnimation(0, toXDelta, 0, toYDelta); + moveAnimation.setDuration(animatedTransitionDuration); + moveAnimation.setStartOffset(0); + moveAnimation.setFillAfter(true); + moveAnimation.setInterpolator(decelerateInterpolator); + scaleAndMove.addAnimation(moveAnimation); + + // Physically move the tile when the animation ends + scaleAndMove.setAnimationListener(new AnimationListener() { + + @Override + public void onAnimationStart(Animation animation) { } + + @Override + public void onAnimationRepeat(Animation animation) { } + + @Override + public void onAnimationEnd(Animation animation) { + FrameLayout.LayoutParams lp = new FrameLayout.LayoutParams( + (int)targetPosition.getWidth(), + (int)targetPosition.getHeight(), + Gravity.TOP + Gravity.LEFT); + lp.setMargins((int)targetPosition.getX(), + (int)targetPosition.getY(), 0, 0); + + currentTile.setLayoutParams(lp); + + // The following null animation just gets rid of screen flicker + animation = new TranslateAnimation(0.0f, 0.0f, 0.0f, 0.0f); + animation.setDuration(1); + currentTile.startAnimation(animation); + } + }); + + // Scale + if (currentPosition != null) { + ScaleAnimation scaleAnimation = + new ScaleAnimation(1, + targetPosition.getWidth() / currentPosition.getWidth(), + 1, + targetPosition.getHeight() / currentPosition.getHeight(), + Animation.ABSOLUTE, 0, + Animation.ABSOLUTE, 0); + + scaleAnimation.setDuration(animatedTransitionDuration); + scaleAnimation.setStartOffset(0); + scaleAnimation.setFillAfter(true); + scaleAndMove.addAnimation(scaleAnimation); + } + + // Set animation to the tile + currentTile.setAnimation(scaleAndMove); + } + // Add to the total animation set + animationSet.addAnimation(scaleAndMove); + } + + if (animationSet.getAnimations().size() > 0) { + Log.d(TAG, "Starting animation"); + animationSet.setFillAfter(true); + animationSet.start(); + } + } + + +} diff --git a/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayoutPreset.java b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayoutPreset.java new file mode 100644 index 000000000..76a13d73b --- /dev/null +++ b/androidgcs/src/com/MobileAnarchy/Android/Widgets/TilesLayout/TilesLayoutPreset.java @@ -0,0 +1,157 @@ +package com.MobileAnarchy.Android.Widgets.TilesLayout; + +import java.util.LinkedList; +import java.util.List; + +/** + * Describes the positioning of a tiles in a 100x100 environment + */ +public class TilesLayoutPreset { + + // ========================================= + // Private Members + // ========================================= + + private List _positions; + private String _presetName; + + // ========================================= + // Constructors + // ========================================= + + public TilesLayoutPreset(String name) { + _presetName = name; + _positions = new LinkedList(); + } + + // ========================================= + // Public Methods + // ========================================= + + public void add(float x, float y, float width, float height) { + TilePosition tilePosition = new TilePosition(x, y, height, width); + add(tilePosition); + } + + public void add(TilePosition tilePosition) { + _positions.add(tilePosition); + } + + public Iterable getTilePositions() { + return _positions; + } + + public int getCount() { + return _positions.size(); + } + + // ========================================= + // Static Presets Factories + // ========================================= + + public static TilesLayoutPreset get1x1() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 1X1"); + preset.add(0, 0, 100, 100); + return preset; + } + + + public static TilesLayoutPreset get1x2() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 1X2"); + preset.add(0, 0, 50, 100); + preset.add(0, 50, 50, 100); + return preset; + } + + + public static TilesLayoutPreset get2x1() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 2X1"); + preset.add(0, 0, 100, 50); + preset.add(50, 0, 100, 50); + return preset; + } + + + public static TilesLayoutPreset get2x2() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 2X2"); + preset.add(0, 0, 50, 50); + preset.add(50, 0, 50, 50); + preset.add(0, 50, 50, 50); + preset.add(50, 50, 50, 50); + return preset; + } + + public static TilesLayoutPreset get3x3() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 3X3"); + preset.add(0, 0, 100/3f, 100/3f); + preset.add(100/3f, 0, 100/3f, 100/3f); + preset.add(200/3f, 0, 100/3f, 100/3f); + preset.add(0, 100/3f, 100/3f, 100/3f); + preset.add(100/3f, 100/3f, 100/3f, 100/3f); + preset.add(200/3f, 100/3f, 100/3f, 100/3f); + preset.add(0, 200/3f, 100/3f, 100/3f); + preset.add(100/3f, 200/3f, 100/3f, 100/3f); + preset.add(200/3f, 200/3f, 100/3f, 100/3f); + return preset; + } + + public static TilesLayoutPreset get3x2() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 3X2"); + preset.add(0, 0, 50, 100/3f); + preset.add(100/3f, 0, 50, 100/3f); + preset.add(200/3f, 0, 50, 100/3f); + preset.add(0, 50, 50, 100/3f); + preset.add(100/3f, 50, 50, 100/3f); + preset.add(200/3f, 50, 50, 100/3f); + return preset; + } + + public static TilesLayoutPreset get2x3() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 2X3"); + preset.add(0, 0, 100/3f, 50); + preset.add(50, 0, 100/3f, 50); + preset.add(0, 100/3f, 100/3f, 50); + preset.add(50, 100/3f, 100/3f, 50); + preset.add(0, 200/3f, 100/3f, 50); + preset.add(50, 200/3f, 100/3f, 50); + return preset; + } + + + public static TilesLayoutPreset get4x4() { + TilesLayoutPreset preset = new TilesLayoutPreset("Default 2X2"); + preset.add(0, 0, 25, 25); + preset.add(25, 0, 25, 25); + preset.add(50, 0, 25, 25); + preset.add(75, 0, 25, 25); + preset.add(0, 25, 25, 25); + preset.add(25, 25, 25, 25); + preset.add(50, 25, 25, 25); + preset.add(75, 25, 25, 25); + preset.add(0, 50, 25, 25); + preset.add(25, 50, 25, 25); + preset.add(50, 50, 25, 25); + preset.add(75, 50, 25, 25); + preset.add(0, 75, 25, 25); + preset.add(25, 75, 25, 25); + preset.add(50, 75, 25, 25); + preset.add(75, 75, 25, 25); + return preset; + } + + public static TilesLayoutPreset get2x3x3() { + TilesLayoutPreset preset = new TilesLayoutPreset("Custom 2X4X4"); + preset.add(0, 0, 50, 50); + preset.add(50, 0, 50, 50); + preset.add(0, 50, 50, 50); + + preset.add(50, 50, 25, 25); + preset.add(75, 50, 25, 25); + preset.add(50, 75, 25, 25); + preset.add(75, 75, 25, 25); + + return preset; + } + + +} From b7cd02c9bfb32738ec339e3877b694801baeede2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 21:02:05 -0500 Subject: [PATCH 260/543] AndroidGCS: Refactor the UAVO browser to use a split view - objects names on the side and content on the other side. Add a filter for settings versus data. --- androidgcs/res/layout/object_browser.xml | 54 +++++++++++- androidgcs/res/layout/pfd.xml | 34 ++++++-- .../openpilot/androidgcs/ObjectBrowser.java | 84 +++++++++++++------ .../src/org/openpilot/uavtalk/UAVObject.java | 9 +- .../org/openpilot/uavtalk/UAVObjectField.java | 6 +- 5 files changed, 151 insertions(+), 36 deletions(-) diff --git a/androidgcs/res/layout/object_browser.xml b/androidgcs/res/layout/object_browser.xml index 9c7456915..67dc0af76 100644 --- a/androidgcs/res/layout/object_browser.xml +++ b/androidgcs/res/layout/object_browser.xml @@ -2,6 +2,56 @@ - - + + + + + + + + + + + + + + + + + + + + + + diff --git a/androidgcs/res/layout/pfd.xml b/androidgcs/res/layout/pfd.xml index 191a80eb9..5291f2724 100644 --- a/androidgcs/res/layout/pfd.xml +++ b/androidgcs/res/layout/pfd.xml @@ -1,8 +1,30 @@ - - - + + + + + + + + + + + + + diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java index a6ed177a2..1a7495ada 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectBrowser.java @@ -16,8 +16,12 @@ import android.util.Log; import android.view.View; import android.widget.AdapterView; import android.widget.ArrayAdapter; +import android.widget.CheckBox; +import android.widget.CompoundButton; +import android.widget.CompoundButton.OnCheckedChangeListener; import android.widget.ListView; import android.widget.Spinner; +import android.widget.TextView; import android.widget.Toast; import android.widget.AdapterView.OnItemClickListener; @@ -27,6 +31,7 @@ import org.openpilot.uavtalk.UAVObject; public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPreferenceChangeListener { private final String TAG = "ObjectBrower"; + int selected_index = -1; boolean connected; SharedPreferences prefs; ArrayAdapter adapter; @@ -35,10 +40,15 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref final Handler uavobjHandler = new Handler(); final Runnable updateText = new Runnable() { public void run() { - Log.d(TAG,"Update"); - update(); + updateObject(); } }; + + private final Observer updatedObserver = new Observer() { + public void update(Observable observable, Object data) { + uavobjHandler.post(updateText); + } + }; /** Called when the activity is first created. */ @Override @@ -47,20 +57,48 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref setContentView(R.layout.object_browser); prefs = PreferenceManager.getDefaultSharedPreferences(this); prefs.registerOnSharedPreferenceChangeListener(this); - - Spinner objectFilter = (Spinner) findViewById(R.id.object_list_filter); } @Override void onOPConnected() { Toast.makeText(this,"Telemetry estabilished",Toast.LENGTH_SHORT); Log.d(TAG, "onOPConnected()"); + + OnCheckedChangeListener checkListener = new OnCheckedChangeListener() { + @Override + public void onCheckedChanged(CompoundButton buttonView, + boolean isChecked) { + updateList(); + } + }; + + ((CheckBox) findViewById(R.id.dataCheck)).setOnCheckedChangeListener(checkListener); + ((CheckBox) findViewById(R.id.settingsCheck)).setOnCheckedChangeListener(checkListener); + + updateList(); + } + + /** + * Populate the list of UAVO objects based on the selected filter + */ + private void updateList() { + // Disconnect any previous signals + if (selected_index > 0) + allObjects.get(selected_index).removeUpdatedObserver(updatedObserver); + selected_index = -1; + + boolean includeData = ((CheckBox) findViewById(R.id.dataCheck)).isChecked(); + boolean includeSettings = ((CheckBox) findViewById(R.id.settingsCheck)).isChecked(); List> allobjects = objMngr.getDataObjects(); allObjects = new ArrayList(); ListIterator> li = allobjects.listIterator(); while(li.hasNext()) { - allObjects.addAll(li.next()); + List objects = li.next(); + if(includeSettings && objects.get(0).isSettings()) + allObjects.addAll(objects); + else if (includeData && !objects.get(0).isSettings()) + allObjects.addAll(objects); } adapter = new ArrayAdapter(this,R.layout.object_view, allObjects); @@ -70,29 +108,25 @@ public class ObjectBrowser extends ObjectManagerActivity implements OnSharedPref objects.setOnItemClickListener(new OnItemClickListener() { public void onItemClick(AdapterView parent, View view, int position, long id) { - /*Toast.makeText(getApplicationContext(), ((TextView) view).getText(), - Toast.LENGTH_SHORT).show();*/ - Intent intent = new Intent(ObjectBrowser.this, ObjectEditor.class); - intent.putExtra("org.openpilot.androidgcs.ObjectName", allObjects.get(position).getName()); - intent.putExtra("org.openpilot.androidgcs.ObjectId", allObjects.get(position).getObjID()); - intent.putExtra("org.openpilot.androidgcs.InstId", allObjects.get(position).getInstID()); - startActivity(intent); + + if (selected_index > 0) + allObjects.get(selected_index).removeUpdatedObserver(updatedObserver); + + selected_index = position; + allObjects.get(position).addUpdatedObserver(updatedObserver); + updateObject(); } }); - - - UAVObject obj = objMngr.getObject("SystemStats"); - if(obj != null) - obj.addUpdatedObserver(new Observer() { - public void update(Observable observable, Object data) { - uavobjHandler.post(updateText); - } - }); - + } - - public void update() { - adapter.notifyDataSetChanged(); + + private void updateObject() { + //adapter.notifyDataSetChanged(); + TextView text = (TextView) findViewById(R.id.object_information); + if (selected_index >= 0 && selected_index < allObjects.size()) + text.setText(allObjects.get(selected_index).toStringData()); + else + Log.d(TAG,"Update called but invalid index: " + selected_index); } public void onSharedPreferenceChanged(SharedPreferences sharedPreferences, diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java index 28c279040..087d2b808 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObject.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObject.java @@ -52,6 +52,11 @@ public abstract class UAVObject { } private CallbackListener updatedListeners = new CallbackListener(this); + public void removeUpdatedObserver(Observer o) { + synchronized(updatedListeners) { + updatedListeners.deleteObserver(o); + } + } public void addUpdatedObserver(Observer o) { synchronized(updatedListeners) { updatedListeners.addObserver(o); @@ -730,14 +735,14 @@ public abstract class UAVObject { */ @Override public String toString() { - return toStringBrief() + toStringData(); + return toStringBrief(); // + toStringData(); } /** * Return a string with the object information (only the header) */ public String toStringBrief() { - return getName() + " (" + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; + return getName(); // + " (" + Integer.toHexString(getObjID()) + " " + Integer.toHexString(getInstID()) + " " + getNumBytes() + ")\n"; } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index 3ed221079..af707d3a0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -469,7 +469,11 @@ public class UAVObjectField { public String toString() { String sout = new String(); - sout += name + ": " + data.toString() + " (" + units + ")\n"; + sout += name + ": " + getValue().toString(); + if (units.length() > 0) + sout += " (" + units + ")\n"; + else + sout += "\n"; return sout; } From 0348a8921eb3d25adf8175b566235b2c3d1e3145 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 22:20:00 -0500 Subject: [PATCH 261/543] AndroidGCS: Output all fields from the UAVObjects --- androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index af707d3a0..988642ff0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -469,7 +469,14 @@ public class UAVObjectField { public String toString() { String sout = new String(); - sout += name + ": " + getValue().toString(); + sout += name + ": "; + for (int i = 0; i < numElements; i++) { + sout += getValue(i).toString(); + if (i != numElements-1) + sout += ", "; + else + sout += " "; + } if (units.length() > 0) sout += " (" + units + ")\n"; else From 3a3ac552da368015b5a87e00991a4903b6a1cea5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 4 Aug 2012 23:00:25 -0500 Subject: [PATCH 262/543] AndroidGCS: Refine the graphics of the object editor --- androidgcs/AndroidManifest.xml | 4 +- androidgcs/res/layout/object_browser.xml | 71 ++++++++--- androidgcs/res/layout/object_edit.xml | 9 -- androidgcs/res/layout/object_editor.xml | 49 +++++++- .../openpilot/androidgcs/ObjectBrowser.java | 19 ++- .../openpilot/androidgcs/ObjectEditView.java | 117 ++++++++---------- .../openpilot/androidgcs/ObjectEditor.java | 18 ++- 7 files changed, 179 insertions(+), 108 deletions(-) delete mode 100644 androidgcs/res/layout/object_edit.xml diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index 40b08c328..52bf9cb30 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -2,14 +2,14 @@ - + - + diff --git a/androidgcs/res/layout/object_browser.xml b/androidgcs/res/layout/object_browser.xml index 67dc0af76..567c04f15 100644 --- a/androidgcs/res/layout/object_browser.xml +++ b/androidgcs/res/layout/object_browser.xml @@ -1,10 +1,13 @@ - + - + + + - - - + android:drawSelectorOnTop="true" + android:choiceMode="singleChoice"/> + + + + + + + + + + + - - diff --git a/androidgcs/res/layout/object_editor.xml b/androidgcs/res/layout/object_editor.xml index d93b1a097..be6e219e8 100644 --- a/androidgcs/res/layout/object_editor.xml +++ b/androidgcs/res/layout/object_editor.xml @@ -1,6 +1,45 @@ - - + + + + + + + + + + + + + + + android:layout_column="1" + android:layout_gravity="center" + android:layout_row="0" + android:layout_rowSpan="2" + android:background="@android:color/transparent" + android:drawableTop="@drawable/ic_map" + android:text="@string/location_name" /> + android:layout_column="2" + android:layout_gravity="center" + android:layout_row="0" + android:layout_rowSpan="2" + android:background="@android:color/transparent" + android:drawableTop="@drawable/ic_pfd" + android:text="@string/pfd_name" /> - \ No newline at end of file +